Module ee_cart_imped_action :: Class EECartImpedClient
[frames] | no frames]

Class EECartImpedClient

source code

A wrapper around the simple simple action client for the EECartImpedAction.

See the actionlib documentation for more details on action clients.

Instance Methods
 
__init__(self, arm_name)
Initialization of the client.
source code
 
moveToPoseStamped(self, pose_stamped, time)
Moves the arm to a pose stamped using the force/impedance controller.
source code
 
addTrajectoryPoint(self, x, y, z, ox, oy, oz, ow, fx, fy, fz, tx, ty, tz, isfx, isfy, isfz, istx, isty, istz, time, frame_id='')
Add a trajectory point to the current goal.
source code
 
trajectoryTime(self)
Returns: The total time of the stored trajectory.
source code
 
sendGoal(self, wait=True)
Sends the stored trajectory to the action server.
source code
 
resetGoal(self)
Resets the stored trajectory to be an empty trajectory.
source code
 
cancelGoal(self)
Cancels the current goal.
source code
 
cancelAllGoals(self)
Cancels all goals on the action server.
source code
Instance Variables
  arm_name
The name of the arm this client executes on.
  client
The simple action client used to communicate with the action server.
  goal
The current stored trajectory.
Method Details

__init__(self, arm_name)
(Constructor)

source code 

Initialization of the client.

Parameters:
  • arm_name (string) - Which arm. Must either be 'right_arm' or 'left_arm'.

moveToPoseStamped(self, pose_stamped, time)

source code 

Moves the arm to a pose stamped using the force/impedance controller.

Parameters:
  • pose_stamped (geometry_msgs.msg.PoseStamped) - The pose to move the end effector to.
  • time (double) - The time after which this goal should be completed.

addTrajectoryPoint(self, x, y, z, ox, oy, oz, ow, fx, fy, fz, tx, ty, tz, isfx, isfy, isfz, istx, isty, istz, time, frame_id='')

source code 

Add a trajectory point to the current goal.

Parameters:
  • x (double) - x position of the end effector
  • y (double) - y position of the end effector
  • z (double) - z position of the end effector
  • ox (double) - x component of the quaternion for the end effector rotation
  • oy (double) - y component of the quaternion for the end effector rotation
  • oz (double) - z component of the quaternion for the end effector rotation
  • ow (double) - w component of the quaternion for the end effector rotation
  • fx (double) - force or stiffness in the x direction
  • fy (double) - force or stiffness in the y direction
  • fz (double) - force or stiffness in the z direction
  • tx (double) - torque or stiffness around the x axis
  • ty (double) - torque or stiffness around the y axis
  • tz (double) - torque or stiffness around the z axis
  • isfx (boolean) - True if this point should exert the given force in the x direction, false if it should achieve a position in the x direction with the given stiffness.
  • isfy (boolean) - True if this point should exert the given force in the y direction, false if it should achieve a position in the y direction with the given stiffness.
  • isfz (boolean) - True if this point should exert the given force in the z direction, false if it should achieve a position in the z direction with the given stiffness.
  • istx (boolean) - True if this point should exert the given torque around the x axis, false if it should achieve an orientation around the x axis with the given stiffness.
  • isty (boolean) - True if this point should exert the given torque around the y axis, false if it should achieve an orientation around the y axis with the given stiffness.
  • istz (boolean) - True if this point should exert the given torque around the z axis, false if it should achieve an orientation around the z axis with the given stiffness.
  • time (boolean) - The time from start when this point should be achieved. Note that this is NOT the time from the last point, but the time from when the entire trajectory is begun.
  • frame_id (string) - The frame id of this point. If left as an empty string will be assumed that the point is in the frame of the root link of the chain for ee_cart_imped_control (likely torso_lift_link).

trajectoryTime(self)

source code 
Returns:
The total time of the stored trajectory.

sendGoal(self, wait=True)

source code 

Sends the stored trajectory to the action server.

Parameters:
  • wait (boolean) - If true, this function will wait for the goal to complete before returning. If false, this function will return immediately upon sending the goal.
Returns:
The state of the simple action client.

cancelGoal(self)

source code 

Cancels the current goal. The arm will hold its current position.

cancelAllGoals(self)

source code 

Cancels all goals on the action server. The arm will hold its current position.