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).
|