Package baxter_interface :: Module limb :: Class Limb
[hide private]
[frames] | no frames]

Class Limb

source code

object --+
         |
        Limb

Interface class for a limb on the Baxter robot.

Nested Classes [hide private]
  Point
Point(x, y, z)
  Quaternion
Quaternion(x, y, z, w)
Instance Methods [hide private]
 
__init__(self, limb)
Constructor.
source code
 
_on_joint_states(self, msg) source code
 
_on_endpoint_states(self, msg) source code
[str]
joint_names(self)
Return the names of the joints for the specified limb.
source code
float
joint_angle(self, joint)
Return the requested joint angle.
source code
dict({str:float})
joint_angles(self)
Return all joint angles.
source code
float
joint_velocity(self, joint)
Return the requested joint velocity.
source code
dict({str:float})
joint_velocities(self)
Return all joint velocities.
source code
float
joint_effort(self, joint)
Return the requested joint effort.
source code
dict({str:float})
joint_efforts(self)
Return all joint efforts.
source code
dict({str:Limb.Point,str:Limb.Quaternion})
endpoint_pose(self)
Return Cartesian endpoint pose {position, orientation}.
source code
dict({str:Limb.Point,str:Limb.Point})
endpoint_velocity(self)
Return Cartesian endpoint twist {linear, angular}.
source code
dict({str:Limb.Point,str:Limb.Point})
endpoint_effort(self)
Return Cartesian endpoint wrench {force, torque}.
source code
 
set_command_timeout(self, timeout)
Set the timeout in seconds for the joint controller
source code
 
exit_control_mode(self, timeout=0.2)
Clean exit from advanced control modes (joint torque or velocity).
source code
 
set_joint_position_speed(self, speed)
Set ratio of max joint speed to use during joint position moves.
source code
 
set_joint_positions(self, positions, raw=False)
Commands the joints of this limb to the specified positions.
source code
 
set_joint_velocities(self, velocities)
Commands the joints of this limb to the specified velocities.
source code
 
set_joint_torques(self, torques)
Commands the joints of this limb to the specified torques.
source code
 
move_to_neutral(self, timeout=15.0)
Command the joints to the center of their joint ranges
source code
 
move_to_joint_positions(self, positions, timeout=15.0, threshold=0.008726646)
(Blocking) Commands the limb to the provided positions.
source code

Inherited from object: __delattr__, __format__, __getattribute__, __hash__, __new__, __reduce__, __reduce_ex__, __repr__, __setattr__, __sizeof__, __str__, __subclasshook__

Properties [hide private]

Inherited from object: __class__

Method Details [hide private]

__init__(self, limb)
(Constructor)

source code 

Constructor.

Parameters:
  • limb (str) - limb to interface
Overrides: object.__init__

joint_names(self)

source code 

Return the names of the joints for the specified limb.

Returns: [str]
ordered list of joint names from proximal to distal (i.e. shoulder to wrist).

joint_angle(self, joint)

source code 

Return the requested joint angle.

Parameters:
  • joint (str) - name of a joint
Returns: float
angle in radians of individual joint

joint_angles(self)

source code 

Return all joint angles.

Returns: dict({str:float})
unordered dict of joint name Keys to angle (rad) Values

joint_velocity(self, joint)

source code 

Return the requested joint velocity.

Parameters:
  • joint (str) - name of a joint
Returns: float
velocity in radians/s of individual joint

joint_velocities(self)

source code 

Return all joint velocities.

Returns: dict({str:float})
unordered dict of joint name Keys to velocity (rad/s) Values

joint_effort(self, joint)

source code 

Return the requested joint effort.

Parameters:
  • joint (str) - name of a joint
Returns: float
effort in Nm of individual joint

joint_efforts(self)

source code 

Return all joint efforts.

Returns: dict({str:float})
unordered dict of joint name Keys to effort (Nm) Values

endpoint_pose(self)

source code 

Return Cartesian endpoint pose {position, orientation}.

Returns: dict({str:Limb.Point,str:Limb.Quaternion})
position and orientation as named tuples in a dict

pose = {'position': (x, y, z), 'orientation': (x, y, z, w)}

  • 'position': Cartesian coordinates x,y,z in namedtuple Limb.Point
  • 'orientation': quaternion x,y,z,w in named tuple Limb.Quaternion

endpoint_velocity(self)

source code 

Return Cartesian endpoint twist {linear, angular}.

Returns: dict({str:Limb.Point,str:Limb.Point})
linear and angular velocities as named tuples in a dict

twist = {'linear': (x, y, z), 'angular': (x, y, z)}

  • 'linear': Cartesian velocity in x,y,z directions in namedtuple Limb.Point
  • 'angular': Angular velocity around x,y,z axes in named tuple Limb.Point

endpoint_effort(self)

source code 

Return Cartesian endpoint wrench {force, torque}.

Returns: dict({str:Limb.Point,str:Limb.Point})
force and torque at endpoint as named tuples in a dict

wrench = {'force': (x, y, z), 'torque': (x, y, z)}

  • 'force': Cartesian force on x,y,z axes in namedtuple Limb.Point
  • 'torque': Torque around x,y,z axes in named tuple Limb.Point

set_command_timeout(self, timeout)

source code 

Set the timeout in seconds for the joint controller

Parameters:
  • timeout (float) - timeout in seconds

exit_control_mode(self, timeout=0.2)

source code 

Clean exit from advanced control modes (joint torque or velocity).

Resets control to joint position mode with current positions.

Parameters:
  • timeout (float) - control timeout in seconds [0.2]

set_joint_position_speed(self, speed)

source code 

Set ratio of max joint speed to use during joint position moves.

Set the proportion of maximum controllable velocity to use during joint position control execution. The default ratio is `0.3`, and can be set anywhere from [0.0-1.0] (clipped). Once set, a speed ratio will persist until a new execution speed is set.

Parameters:
  • speed (float) - ratio of maximum joint speed for execution default= 0.3; range= [0.0-1.0]

set_joint_positions(self, positions, raw=False)

source code 

Commands the joints of this limb to the specified positions.

IMPORTANT: 'raw' joint position control mode allows for commanding joint positions, without modification, directly to the JCBs (Joint Controller Boards). While this results in more unaffected motions, 'raw' joint position control mode bypasses the safety system modifications (e.g. collision avoidance). Please use with caution.

Parameters:
  • positions (dict({str:float})) - joint_name:angle command
  • raw (bool) - advanced, direct position control mode

set_joint_velocities(self, velocities)

source code 

Commands the joints of this limb to the specified velocities.

IMPORTANT: set_joint_velocities must be commanded at a rate great than the timeout specified by set_command_timeout. If the timeout is exceeded before a new set_joint_velocities command is received, the controller will switch modes back to position mode for safety purposes.

Parameters:
  • velocities (dict({str:float})) - joint_name:velocity command

set_joint_torques(self, torques)

source code 

Commands the joints of this limb to the specified torques.

IMPORTANT: set_joint_torques must be commanded at a rate great than the timeout specified by set_command_timeout. If the timeout is exceeded before a new set_joint_torques command is received, the controller will switch modes back to position mode for safety purposes.

Parameters:
  • torques (dict({str:float})) - joint_name:torque command

move_to_neutral(self, timeout=15.0)

source code 

Command the joints to the center of their joint ranges

Neutral is defined as:

 ['*_s0', '*_s1', '*_e0', '*_e1', '*_w0', '*_w1', '*_w2']
 [0.0, -0.55, 0.0, 0.75, 0.0, 1.26, 0.0]
Parameters:
  • timeout (float) - seconds to wait for move to finish [15]

move_to_joint_positions(self, positions, timeout=15.0, threshold=0.008726646)

source code 

(Blocking) Commands the limb to the provided positions.

Waits until the reported joint state matches that specified.

This function uses a low-pass filter to smooth the movement.

Parameters:
  • positions (dict({str:float})) - joint_name:angle command
  • timeout (float) - seconds to wait for move to finish [15]
  • threshold (float) - position threshold in radians across each joint when move is considered successful [0.008726646]