Cartesian Pose Controller

Overview

The Cartesian Pose Controller commands a desired pose to a chain of joints. The chain of joints is a set of joints that spans from some link (the "root" link) to another link (the "tip" link). The poses are applied at the origin of the tip link in the frame of the root link, and are controlled by PID controllers. Translational and rotational gains are set separately.

ROS API

Subscribed Topics

command (geometry_msgs/Pose)
  • The pose to command

Parameters

root_name (string, default: Required)
  • The root link of the chain of joints
tip_name (string, default: Required)
  • The tip link of the chain of joints
fb_trans/p (double, default: Required)
  • Translational gain, relating force to position error
fb_trans/d (double, default: 0.0)
  • Translational derivative gain
fb_trans/i (double, default: 0.0)
  • Translational integral gain
fb_trans/i_clamp (double, default: 0.0)
  • Bounds enforced on the translational integral windup
fb_rot/p (double, default: Required)
  • Rotational gain, relating end-effector torques to orientation error
fb_rot/d (double, default: 0.0)
  • Rotational derivative gain
fb_rot/i (double, default: 0.0)
  • Rotational integral gain
fb_rot/i_clamp (double, default: 0.0)
  • Bounds enforced on the rotational integral windup

Example configuration

r_arm_cartesian_pose_controller:
  type: CartesianPoseController
  root_name: torso_lift_link
  tip_name: r_wrist_roll_link
  fb_trans:
    p: 20.0
    i: 0.5
    d: 0.0
    i_clamp: 1.0
  fb_rot:
    p: 0.5
    i: 0.1
    d: 0.0
    i_clamp: 0.2

Wiki: robot_mechanism_controllers/CartesianPoseController (last edited 2011-08-29 10:39:14 by Luis Roalter)