JT Cartesian Controller
Contents
Overview
The JT Cartesian Controller controls the pose of the end effector using a Jacobian-transpose based controller, with redundancy control.
It's loosely based off the acceleration control scheme in Nakanishi, Comparative Experiements on Task Space Control, with a diagonal approximation of the mass matrix, and the Jacobian derivatives set to zero. These simplifications have worked well in practice when controlling the PR2.
ROS API
Parameters
root_name (string, default: Required)- The root link of the chain to control.
- The tip link (end effector) of the chain to control.
- Proportional gain for translation of the end effector.
- Derivative gain for translation of the end effector
- Proportional gain for rotation of the end effector
- Derivative gain for rotation of the end effector
- Velocity limit for translation (m/s). Zero means not limited.
- Velocity limit for rotation (rad/s). Zero means not limited.
- Damping term for taking the inverse of the Jacobian.
- Feedforward term for the posture controller.
- Maximum torque for the joint.
- Gain on the posture control.
Example configuration (from pr2_controller_configuration/pr2_jt_controllers.yaml):
r_cart:
type: robot_mechanism_controllers/JTCartesianController
root_name: torso_lift_link
tip_name: r_gripper_tool_frame
k_posture: 25.0
jacobian_inverse_damping: 0.01
pose_command_filter: 0.01
cart_gains:
trans:
p: 800.0
d: 15.0
rot:
p: 80.0
d: 1.2
joint_feedforward:
r_shoulder_pan_joint: 3.33
r_shoulder_lift_joint: 1.16
r_upper_arm_roll_joint: 0.1
r_elbow_flex_joint: 0.25
r_forearm_roll_joint: 0.133
r_wrist_flex_joint: 0.0727
r_wrist_roll_joint: 0.0727
joint_max_effort:
r_shoulder_pan_joint: 11.88
r_shoulder_lift_joint: 11.64
r_upper_arm_roll_joint: 6.143
r_elbow_flex_joint: 6.804
r_forearm_roll_joint: 8.376
r_wrist_flex_joint: 5.568
r_wrist_roll_joint: 5.568
vel_saturation_trans: 2.0
vel_saturation_rot: 4.0
Published Topics
state (robot_mechanism_controllers/JTCartesianControllerState)- Current state of the controller
- Current setpoint of the controller
Subscribed Topics
command_pose (geometry_msgs/PoseStamped)- Tells the controller where to go.
- New gains. 6 values replaces all the Kp terms (trans, trans, trans, rot, rot, rot). 12 Replaces the Kp and Kd terms.
- New desired joint posture. Should have the same size as the number of joints being controlled.







