Gravity Compensation Controller
Controller that calculates and commands feed forward torques for the current configuration and velocities.
It is recommended to always run this controller as it vastly improves the control performance.
Parameters
Definition:
gravity_compensation_controller:
joints:
type: string_array
default_value: []
description: "Names of joints used by the controller"
validation:
unique<>: null
arm_name:
type: string
default_value: "dynaarm"
description: "name of the arm hardware interface"
enable_state_topic:
type: bool
default_value: true
description: "Publish a status message on the ~/state topic"
joints | [Required]:
List of managed joints by the controller. Always needs to be a list of all joints of an arm in the order specified in the urdf
arm_name | [Required]:
Name of the arm as specified in the ros2control part of the urdf. Currently this is ${tf_prefix}DynaarmSystem
Example:
A full example can be found in the dynaarm_demo repository.
gravity_compensation_controller:
ros__parameters:
joints:
- shoulder_rotation
- shoulder_flexion
- elbow_flexion
- forearm_rotation
- wrist_flexion
- wrist_rotation
arm_name: DynaarmSystem
ROS Interfacing
None
Additional Information
The controller uses internally the pinnocchio::rnea function in order to calculate the inverse dynamics.
As written above it is recommend to always run this controller. The only reason not to run this controller is in you want to command custom torques to the arm.\ The controller does not allow controller chaining at the moment.