Previous topic

Karpal API Notes

This Page

karpal_lib Module

Created on 2016-01-20 @author: Andrew H. Fagg and Bonnie Pope

class karpal_lib.Karpal[source]

Karpal control tools.

Variables:
JPOSITION_CRANE = {'s1': -0.7853981633974483, 's0': 0, 'w2': 0, 'w1': 0.7853981633974483, 'w0': 0, 'e1': 1.5707963267948966, 'e0': 0}

Crane joint angle position. Elbow up and hand oriented downward.

JPOSITION_GRASP_READY = {'s1': -0.7853981633974483, 's0': 0, 'w2': 0, 'w1': -0.7853981633974483, 'w0': 0, 'e1': 1.5707963267948966, 'e0': 0}

Grasp ready angle position. Elbow up and forearm and hand oriented horizontally (45 degrees off center).

JPOSITION_PARK = {'s1': 0.39269908169872414, 's0': 0, 'w2': 0, 'w1': 0.39269908169872414, 'w0': 0, 'e1': 0.7853981633974483, 'e0': 0}

Park angle position. Arm is in a low-energy state where it is safe to be disabled.

JPOSITION_ZERO = {'s1': 0, 's0': 0, 'w2': 0, 'w1': 0, 'w0': 0, 'e1': 0, 'e0': 0}

Zero joint angle position

armMoveToJointPosition(limb='left', orientation={}, timeout=15.0)[source]

Move arm to a specified joint position.

Parameters:
  • limb – ‘left’ or ‘right’
  • orientation – dict containing the joint angles of interest. The elements can be either specific joints (including limb) or generic joints. In the latter case, the specified limb is appended
  • timeout – Number of seconds to wait for movement to complete (default = 15.0 sec)
calibrateGripper(limb)[source]

Calibrate the specified gripper

Parameters:limb – Side to calibrate. Either ‘left’ or ‘right’
calibrateLeftGripper()[source]

Calibrate the positional offset of the left gripper.

calibrateRightGripper()[source]

Calibrate the positional offset of the right gripper.

closeGripper(limb)[source]

Close the specified gripper until a force threshold.

Parameters:limb – Side to close. Either ‘left’ or ‘right’
closeLeftGripper()[source]

Close the left gripper until a force threshold.

closeRightGripper()[source]

Close the right gripper until a force threshold.

computeHorizontalOrientation(orient, handFlip=0)[source]

Compute a hand orientation in which the hand is in the horizontal plane

Parameters:
  • orient – Orientation of the hand in the robots coordinate frame (about Z)
  • handFlip – Enables addition of a flipped hand (still horizontal, though) if set to PI
Returns:

Quaternion describing the full orientation

computeVerticalOrientation(orient)[source]

Compute a hand orientation in which the hand is pointed downwards

Parameters:orient – Orientation of the hand in the robot coordinate frame (about Z)
Returns:Quaternion describing the full orientation
disable()[source]

Disable the robot.

enable()[source]

Enable the robot.

Note

The robot’s E-Stop button must be disabled in order for this function to be successful (this is the big red button).

findAbsoluteJogSolution(limb='left', deltaX=[0, 0, 0])[source]

Compute the inverse kinematics solution for a small change in position. The change is specified in the robot base coordinate frame.

Parameters:
  • limb – Which limb to compute solution for: left/right
  • deltaX – Three element array: [dX, dY, dZ]
Returns:

None if no solution is found, or a dictionary that contains information about the chosen solution: the joint angles (joint_angles), the full hand orientation (q), position of the limb (position); and the limb that the solution was computed for (limb).

findHorizontalSolution(limb='left', position=[0.6, 0.1, 0.3], minOrient=1.5707963267948966, maxOrient=1.5707963267948966, nAttempts=10)[source]

Find a viable joint solution for a horizontal reach. A range of acceptable orientations in the horizontal plane is specified; one is selected at random. Multiple attempts are tried at finding a valid inverse kinematics solution (up to nAttemts)

Parameters:
  • limb – Determines which limb; ‘left’ or ‘right’
  • position – Goal position of the gripper
  • minOrient – Minimum acceptable hand orientation (in the horiziontal plane)
  • maxOrient – Maximum acceptable hand orientation
  • nAttempts – Maximum number of attempts
Returns:

None if no solution is found, or a dictionary that contains information about the chosen configuration: the solution (joint_angles), the full hand orientation (q), the hand orientation in the horizontal plane (orient); and the limb the solution was computed for (limb).

findRelativeJogSolution(limb='left', deltaX=[0, 0, 0])[source]

Compute the inverse kinematics solution for a small change in position. The change is specified in the hand coordinate frame.

Parameters:
  • limb – Which limb to compute solution for: left/right
  • deltaX – Three element array: [dX, dY, dZ]
Returns:

None if no solution is found, or a dictionary that contains information about the chosen solution: the joint angles (joint_angles), the full hand orientation (q), position of the limb (position); and the limb that the solution was computed for (limb).

findVerticalSolution(limb='left', position=[0.6, 0.1, 0.3], minOrient=0, maxOrient=6.283185307179586, flipFlag=False, nAttempts=10)[source]

Find a viable joint solution for a vertical reach (from above). A range of acceptable orientations about the vertical axis is specified; one is selected at random. Multiple attempts are tried at finding a valid inverse kinematics solution (up to nAttemts)

Parameters:
  • limb – Determines which limb; ‘left’ or ‘right’
  • position – Goal position of the gripper
  • minOrient – Minimum acceptable hand orientation (about the vertical axis)
  • maxOrient – Maximum acceptable hand orientation
  • nAttempts – Maximum number of attempts
Returns:

None if no solution is found, or a dictionary that contains information about the chosen configuration: the solution (joint_angles), the full hand orientation (q), the hand orientation in the horizontal plane (orient); and the limb the solution was computed for (limb).

getArmOrientation(limb)[source]

Get the orientation of the specified hand (base of the hand) in the Baxter’s main coordinate frame.

Parameters:limb – ‘left’ or ‘right’
Returns:A vector containing the unit quaternion
getArmPose(limb)[source]

Get the full pose of the specified limb.

Parameters:limb – ‘left’ or ‘right’
Returns:A dict containing the full pose (keys: ‘position’ and ‘orientation’).
getArmPosition(limb)[source]

Get the Cartesian position of the specified hand (base of the hand) in the Baxter’s main coordinate frame. :param limb: ‘left’ or ‘right’ :returns: A vector containing the position (m)

getJointAngles(limb)[source]

Get the joint configuration of the specified limb.

Parameters:limb – ‘left’ or ‘right’
Returns:A dict of joint angles (rad).
getLeftArmOrientation()[source]

Get the orientation of the left hand (base of the hand) in the Baxter’s main coordinate frame.

Returns:A vector containing the unit quaternion
getLeftArmPosition()[source]

Get the Cartesian position of the left hand (base of the hand) in the Baxter’s main coordinate frame.

Returns:A vector containing the position (m)
getRightArmOrientation()[source]

Get the orientation of the right hand (base of the hand) in the Baxter’s main coordinate frame.

Returns:A vector containing the unit quaternion
getRightArmPosition()[source]

Get the Cartesian position of the right hand (base of the hand) in the Baxter’s main coordinate frame.

Returns:A vector containing the position (m)
inverseKinematics(limb, position, orientation)[source]

Perform the inverse kinematics given a limb, position and orientation

Parameters:
  • limb – ‘left’ or ‘right’
  • position – Vector containing the goal Cartesian position for the base of the hand
  • orientation – Vector containing the goal orientation for the hand (unit quaternion)
Returns:

None if no solution found, or a dict containing the joint angles that correspond to the goal.

moveArm(limb, position, orientation)[source]

Move the arm to a Cartesian goal position/orientation

Parameters:
  • limb – ‘left’ or ‘right’
  • position – Vector containing the goal Cartesian position for the base of the hand
  • orientation – Vector containing the goal orientation for the hand (unit quaternion)
Returns:

None if no solution found, or a dict containing the joint angles that correspond to the goal.

moveArmJoints(limb, angles, timeout=15.0)[source]

Move specified arm to a joint goal

Parameters:
  • limb – ‘left’ or ‘right’
  • angles – A dict (?) containing the joint goal position
  • timeout – Number of seconds before aborting joint movement (default = 15.0 sec)
Returns:

The joint angles

moveArmUntilDistance(limb='left', delta=0.02, maxDistance=0.3, handDistance=70)[source]

Move the arm along the Z axis of the hand until an obstacle is sensed or a maximum distance is achieved.

Warning

Not all obstacles can be sensed with the distance sensor.

Parameters:
  • limb – Determines which limb; ‘left’ or ‘right’
  • delta – Distance to move along the Z axis (m) between sensor checks. This parameter should be positive
  • maxDistance – Maximum distance to move (m)
  • handDistance – Distance to the obstacle to stop at (mm)
Returns:

2 if successfully reached the obstacle; 1 if the maximum distance has been reached; and 0 False if no solution

openGripper(limb)[source]

Open the specified gripper to its widest extent

Parameters:limb – Side to open. Either ‘left’ or ‘right’
openLeftGripper()[source]

Open the left gripper to its widest extent.

openRightGripper()[source]

Open the right gripper to its widest extent.

printTextToScreen(text, scale=3)[source]

Print text to the Baxter screen

Parameters:
  • text – String containing the text to print. Newlines in the string are handled properly.
  • scale – Size of the text.
tiltWrist(limb)[source]

For the specified limb, flip the final wrist joint by pi radians

Parameters:limb – ‘left’ or ‘right’
Returns:True if successful; False if not
karpal_lib.main()[source]

Test function