Joint trajectory impedance controller#
The joint trajectory impedance controller is a controller operating with effort command interfaces. This controller is a combination of two controllers.
The
joint_trajectory_controller
, that computes a reference for the joints based on a desired joint-space trajectory. More information about this controller can be found in the ros2_controllers documentationThe
gravity_compensation_controller
, receives the reference from the joint trajectory controller and computes effort to control the joints. It utilizes spring dynamics at the joint level, which are determined by the joint stiffness and damping parameters defined for each joint.
The joint trajectory impedance controller allows for compliant control at the joint level while still
being able to control the joint position like a normal joint trajectory controller. It enables the
execution of motions using play_motion
or MoveIt
with minimal modifications required for integration
with the new controllers. Moreover, the user can change and tune the default stiffness and damping gains
if needed.
Caution
If you need to change the default stiffness and damping gains of the controller, it is highly recommended to be near the emergency button of the robot. This is because the robot may exhibit unexpected behavior in response to the changes.
Setting up the controller#
To set up the joint trajectory impedance controller, you need to define the parameters for both the joint trajectory controller and the gravity compensation controller.
Below is an example of how to configure the joint trajectory controller for the arm of TIAGO:
arm_impedance_controller:
ros__parameters:
joints:
- arm_1_joint
- arm_2_joint
- arm_3_joint
- arm_4_joint
- arm_5_joint
- arm_6_joint
- arm_7_joint
command_joints:
- gravity_compensation_controller/arm_1_joint
- gravity_compensation_controller/arm_2_joint
- gravity_compensation_controller/arm_3_joint
- gravity_compensation_controller/arm_4_joint
- gravity_compensation_controller/arm_5_joint
- gravity_compensation_controller/arm_6_joint
- gravity_compensation_controller/arm_7_joint
command_interfaces:
- position
- velocity
state_interfaces:
- position
- velocity
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 5.0
joint_1:
goal: 0.02
joint_2:
goal: 0.02
joint_3:
goal: 0.02
joint_4:
goal: 0.02
joint_5:
goal: 0.02
joint_6:
goal: 0.02
joint_7:
goal: 0.02
The employed parameters are defined within the joint trajectory controller :
joints
: The joints that the controller listens to and retrieves the state fromcommand_joints
: The joints that the controller controls, which are the state interfaces of the gravity compensation controllercommand_interfaces
: The interfaces provided by the hardware interface to send commands to the jointsstate_interfaces
: The interfaces provided by the hardware interface to get the state of the jointsconstraints
: The constraints defined in a similar way to traditional joint_trajectory_controllers
Then, here is an example of the gravity compensation controller configuration setup for the arm of TIAGO:
gravity_compensation_controller:
ros__parameters:
command_joints: ['arm_1_joint', 'arm_2_joint', 'arm_3_joint', 'arm_4_joint', 'arm_5_joint', 'arm_6_joint', 'arm_7_joint']
root_link: "torso_fixed_column_link"
tip_links: ["gripper_link"]
torque_gain: 1.0
parameters:
arm_1_joint:
motor_torque_constant: 0.0
reduction_ratio: 100.0
kp: 6.0
kd: 1.0
arm_2_joint:
motor_torque_constant: 0.136
reduction_ratio: 100.0
kp: 6.0
kd: 0.8
arm_3_joint:
motor_torque_constant: -0.087
reduction_ratio: 100.0
kp: -6.0
kd: -0.8
arm_4_joint:
motor_torque_constant: -0.087
reduction_ratio: 100.0
kp: -6.0
kd: -0.8
arm_5_joint:
motor_torque_constant: -1.0
reduction_ratio: 336.0
kp: -0.02
kd: -0.02
arm_6_joint:
motor_torque_constant: 0.0
reduction_ratio: 336.0
kp: 0.2
kd: 0.02
arm_7_joint:
motor_torque_constant: 0.0
reduction_ratio: 336.0
kp: 0.2
kd: 0.02
The employed parameters for the gravity compensation controller are:
command_joints
: The joints controlled by the controller, to which the effort commands are sent.root_link
: The starting link, from which the kinematic chain is defined.tip_links
: The ending links, to which the kinematic chain is defined.torque_gain
: The gain applied to the computed torque.parameters
: The parameters for each joint, which include the motor torque constant, the reduction ratio of the motor, and the stiffness (kp
) and damping (kd
) values defined for each joint.
See also#
You might want to check How to change your robot’s motion controller to know more about how to load and start the controller.