[Documentation] [TitleIndex] [WordIndex

Cartesian Twist Controller

Overview

The Cartesian Twist Controller commands a desired twist 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 twists 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/Twist)

Parameters

root_name (string, default: Required) tip_name (string, default: Required) fb_trans/p (double, default: Required) fb_trans/d (double, default: 0.0) fb_trans/i (double, default: 0.0) fb_trans/i_clamp (double, default: 0.0) fb_rot/p (double, default: Required) fb_rot/d (double, default: 0.0) fb_rot/i (double, default: 0.0) fb_rot/i_clamp (double, default: 0.0)

Example configuration

r_arm_cartesian_twist_controller:
  type: CartesianTwistController
  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

2019-11-16 13:13