Admittance Controller
Admittance controller enables you do zero-force control from a force measured on your TCP.
The controller implements ChainedControllerInterface
, so it is possible to add another controllers in front of it, e.g., JointTrajectoryController
.
The controller requires an external kinematics plugin to function. The kinematics_interface repository provides an interface and an implementation that the admittance controller can use.
ROS 2 interface of the controller
Parameters
The admittance controller uses the generate_parameter_library to handle its parameters. The parameter definition file located in the src folder contains descriptions for all the parameters used by the controller.
- joints (string_array)
Specifies which joints will be used by the controller.
Read only: True
- command_joints (string_array)
(optional) Specifies the joints for writing into another controllers reference. This parameter is only relevant when chaining the output of this controller to the input of another controller.
Read only: True
Default: {}
- command_interfaces (string_array)
Specifies which command interfaces the controller will claim.
Read only: True
- state_interfaces (string_array)
Specifies which state interfaces the controller will claim.
Read only: True
- chainable_command_interfaces (string_array)
Specifies which reference interfaces the controller will export. Normally, the position and velocity are used.
Read only: True
- kinematics.plugin_name (string)
Specifies the name of the kinematics plugin to load.
- kinematics.plugin_package (string)
Specifies the package name that contains the kinematics plugin.
- kinematics.base (string)
Specifies the base link of the robot description used by the kinematics plugin.
- kinematics.tip (string)
Specifies the end effector link of the robot description used by the kinematics plugin.
- kinematics.alpha (double)
Specifies the damping coefficient for the Jacobian pseudo inverse.
Default: 0.01
- ft_sensor.name (string)
Specifies the name of the force torque sensor in the robot description which will be used in the admittance calculation.
- ft_sensor.frame.id (string)
Specifies the frame/link name of the force torque sensor.
- ft_sensor.filter_coefficient (double)
Specifies the filter coefficient for the sensor’s exponential filter.
Default: 0.05
- control.frame.id (string)
Specifies the control frame used for admittance calculation.
- fixed_world_frame.frame.id (string)
Specifies the world frame use for admittance calculation. Gravity must point down in this frame.
- gravity_compensation.frame.id (string)
Specifies the frame which center of gravity (CoG) is defined in. Normally, the force torque sensor frame should be used.
- gravity_compensation.CoG.pos (double_array)
Specifies the position of the center of gravity (CoG) of the end effector in the gravity compensation frame.
Constraints:
length must be equal to 3
- gravity_compensation.CoG.force (double)
Specifies the weight of the end effector, e.g mass * 9.81.
Default: 0.0
- admittance.selected_axes (bool_array)
Specifies whether the axes x, y, z, rx, ry, and rz should be included in the admittance calculation.
Constraints:
length must be equal to 6
- admittance.mass (double_array)
Specifies the mass values for x, y, z, rx, ry, and rz used in the admittance calculation.
Constraints:
length must be equal to 6
each element of array must be within bounds 0.0001
- admittance.damping_ratio (double_array)
Specifies damping ratio values for x, y, z, rx, ry, and rz used in the admittance calculation. The damping ratio is defined as: zeta = D / (2 * sqrt( M * S )).
Constraints:
length must be equal to 6
- admittance.stiffness (double_array)
Specifies the stiffness values for x, y, z, rx, ry, and rz used in the admittance calculation.
Constraints:
length must be equal to 6
each element of array must be within bounds 0.0
- admittance.joint_damping (double)
Specifies the joint damping applied used in the admittance calculation.
Default: 5.0
Constraints:
greater than or equal to 0.0
- enable_parameter_update_without_reactivation (bool)
If enabled, the parameters will be dynamically updated while the controller is running.
Default: true
An example parameter file for this controller can be found in the test folder:
load_admittance_controller:
# contains minimal parameters that need to be set to load controller
ros__parameters:
joints:
- joint1
- joint2
command_interfaces:
- velocity
state_interfaces:
- position
- velocity
chainable_command_interfaces:
- position
- velocity
test_admittance_controller:
# contains minimal needed parameters for kuka_kr6
ros__parameters:
joints:
- joint1
- joint2
- joint3
- joint4
- joint5
- joint6
command_interfaces:
- position
state_interfaces:
- position
chainable_command_interfaces:
- position
- velocity
kinematics:
plugin_name: kinematics_interface_kdl/KinematicsInterfaceKDL
plugin_package: kinematics_interface
base: base_link # Assumed to be stationary
tip: tool0
group_name: arm
alpha: 0.0005
ft_sensor:
name: ft_sensor_name
frame:
id: link_6 # tool0 Wrench measurements are in this frame
external: false # force torque frame exists within URDF kinematic chain
filter_coefficient: 0.005
control:
frame:
id: tool0 # Admittance calcs (displacement etc) are done in this frame. Usually the tool or end-effector
external: false # control frame exists within URDF kinematic chain
fixed_world_frame: # Gravity points down (neg. Z) in this frame (Usually: world or base_link)
frame:
id: base_link # Admittance calcs (displacement etc) are done in this frame. Usually the tool or end-effector
external: false # control frame exists within URDF kinematic chain
gravity_compensation:
frame:
id: tool0
external: false
CoG: # specifies the center of gravity of the end effector
pos:
- 0.1 # x
- 0.0 # y
- 0.0 # z
force: 23.0 # mass * 9.81
admittance:
selected_axes:
- true # x
- true # y
- true # z
- true # rx
- true # ry
- true # rz
# Having ".0" at the end is MUST, otherwise there is a loading error
# F = M*a + D*v + S*(x - x_d)
mass:
- 5.5
- 6.6
- 7.7
- 8.8
- 9.9
- 10.10
damping_ratio: # damping can be used instead: zeta = D / (2 * sqrt( M * S ))
- 2.828427 # x
- 2.828427 # y
- 2.828427 # z
- 2.828427 # rx
- 2.828427 # ry
- 2.828427 # rz
stiffness:
- 214.1
- 214.2
- 214.3
- 214.4
- 214.5
- 214.6
Topics
- ~/joint_references (input topic) [trajectory_msgs::msg::JointTrajectoryPoint]
Target joint commands when controller is not in chained mode.
- ~/wrench_reference (input topic) [geometry_msgs::msg::WrenchStamped]
Target wrench offset (WrenchStamped has to be in the frame of the FT-sensor).
- ~/state (output topic) [control_msgs::msg::AdmittanceControllerState]
Topic publishing internal states.
ros2_control interfaces
References
The controller has position
and velocity
reference interfaces exported in the format:
<controller_name>/<joint_name>/[position|velocity]
States
The state interfaces are defined with joints
and state_interfaces
parameters as follows: <joint>/<state_interface>
.
Supported state interfaces are position
, velocity
, and acceleration
as defined in the hardware_interface/hardware_interface_type_values.hpp.
If some interface is not provided, the last commanded interface will be used for calculation.
For handling TCP wrenches *Force Torque Sensor* semantic component (from package *controller_interface*) is used.
The interfaces have prefix ft_sensor.name
, building the interfaces: <sensor_name>/[force.x|force.y|force.z|torque.x|torque.y|torque.z]
.
Commands
The command interfaces are defined with joints
and command_interfaces
parameters as follows: <joint>/<command_interface>
.
Supported state interfaces are position
, velocity
, and acceleration
as defined in the hardware_interface/hardware_interface_type_values.hpp.