[Documentation] [TitleIndex] [WordIndex

JT Cartesian Controller

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) tip_name (string, default: Required) cart_gain/trans/p (double, default: Required) cart_gains/trans/d (double, default: Required) cart_gains/rot/p (double, default: Required) cart_gains/rot/d (double, default: Required) vel_saturation_trans (double, default: 0.0) vel_saturation_rot (double, default: 0.0) jacobian_inverse_damping (double, default: 0.0) joint_feedforward/<joint> (double, default: 0.0) saturation/<joint> (double, default: 0.0) k_posture (double, default: 1.0)

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) state/x_desi (geometry_msgs/PoseStamped)

Subscribed Topics

command_pose (geometry_msgs/PoseStamped) gains (std_msgs/Float64MultiArray) command_posture (std_msgs/Float64MultiArray)

2019-08-10 13:01