Gravity Compensation

From sdk-wiki
Jump to: navigation, search

Gravity Compensation Torques

In order to oppose the effect of gravitational force acting across Baxter's arm, gravity compensation torques have to be applied across that arm. This is a basic mode that is active from the time the robot is enabled. The built-in gravity compensating model uses KDL for calculating the gravity compensation torques. The springs attached to the S1 joint also require compensation torques, these are found using an internal spring model and applied in conjunction with the torques from KDL. These gravity compensation torques are passed directly to the JCB through a separate channel and are applied irrespective of the controller being active.

The gravity compensation torques are available via the topic robot/limb/<side>/gravity_compensation_torques of message type baxter_core_msgs/SEAJointState

$ rostopic echo robot/limb/<left/right>/gravity_compensation_torques' of message type baxter_core_msgs/SEAJointState

In order to disable the gravity compensation torques, an empty message should be published to the topic /robot/limb/<side>/suppress_gravity_compensation at greater than 5 Hz.

$ rostopic pub -r 10 /robot/limb/<side>/suppress_gravity_compensation std_msgs/Empty


The fields of the Gravity Compensation Torques message:

commanded_position: Commanded Position from RealTime Loop

commanded_velocity: Commanded Velocity from RealTime Loop

commanded_effort: Commanded Effort from RealTime Loop. In torque control mode this will be the torques you commanded. 
                  In position control mode this is the integral effort applied achieving the goal positions.

actual_position: Measured Position from RealTime Loop

actual_velocity: Measured Velocity from RealTime Loop

actual_effort: Measured Effort from RealTime Loop via the Spring Deflection Sensors in each Series Elastic Actuator

gravity_model_effort: Gravity Compensation Torques Commanded

hysteresis_model_effort: Spring Compensation Torques Commanded. This is the hysterisis effort applied to account for spring joint s1

crosstalk_model_effort: Joint Crosstalk Compensation. Present here is minimal compensation for joint s1 crosstalk caused by the arm's downstream joints

hystState: A variable used in calculating the hysteresis model.