ROS & ROS2: Impedance control

Impedance control allows implementation of compliant robot behavior

Joint impedance control

Set joint stiffness

Default service name

Message type (srv)

Limits

Units

/iiwa/set_joint_stiffness

libiiwa_msgs/SetArray

[0.0, Inf)

Nm/rad

Implementation details

# TODO

Example

$ rosservice call /iiwa/set_joint_stiffness "[400.0, 350.0, 300.0, 250.0, 200.0, 150.0, 100.0]"

Set joint damping

Default service name

Message type (srv)

Limits

Units

/iiwa/set_joint_damping

libiiwa_msgs/SetArray

[0.0, 1.0]

unitless

Implementation details

# TODO

Example

$ rosservice call /iiwa/set_joint_damping "[0.7, 0.6, 0.5, 0.4, 0.3, 0.2, 0.1]"

Cartesian impedance control

Set Cartesian stiffness

Default service name

Message type (srv)

Limits

Units

/iiwa/set_cartesian_stiffness

libiiwa_msgs/SetXYZABCParam

translational: [0.0, 5000.0], rotational: [0.0, 300.0], null_space: [0.0, Inf)

translational: N/m, rotational: Nm/rad, null_space: Nm/rad

Implementation details

# TODO

Example

$ rosservice call /iiwa/set_cartesian_stiffness "{x: 2000.0, y: 3000.0, z: 4000.0, a: 50.0, b: 100.0, c: 150.0, float_param: 100.0}"

Set Cartesian damping

Default service name

Message type (srv)

Limits

Units

/iiwa/set_cartesian_damping

libiiwa_msgs/SetXYZABCParam

translational: [0.1, 1.0], rotational: [0.1, 1.0], null_space: [0.3, 0.1]

unitless

Implementation details

# TODO

Example

$ rosservice call /iiwa/set_cartesian_damping "{x: 0.2, y: 0.3, z: 0.4, a: 0.5, b: 0.6, c: 0.7, float_param: 0.5}"

Set Cartesian additional control force

Default service name

Message type (srv)

Limits

Units

/iiwa/set_cartesian_additional_control_force

libiiwa_msgs/SetXYZABC

-

translational: N, rotational: Nm

Implementation details

# TODO

Example

$ rosservice call /iiwa/set_cartesian_additional_control_force "{x: -10.0, y: -20.0, z: -30.0, a: 10.0, b: 20.0, c: 30.0}"

Set Cartesian maximum control force

Default service name

Message type (srv)

Limits

Units

/iiwa/set_cartesian_max_control_force

libiiwa_msgs/SetXYZABCParam

translational: [0.0, Inf), rotational: [0.0, Inf)

translational: N, rotational: Nm

Implementation details

# TODO

Example

$ rosservice call /iiwa/set_cartesian_max_control_force "{x: 10.0, y: 20.0, z: 30.0, a: 10.0, b: 20.0, c: 30.0, boolean_param: true}"

Set Cartesian maximum velocity

Default service name

Message type (srv)

Limits

Units

/iiwa/set_cartesian_max_velocity

libiiwa_msgs/SetXYZABC

translational: [0.0, Inf), rotational: [0.0, Inf)

translational: m/s, rotational: rad/s

Implementation details

# TODO

Example

# abort the motion for a maximum Cartesian velocity of 10  m/s in the z-axis
$ rosservice call /iiwa/set_cartesian_max_velocity "{x: 1.e+6, y: 1.e+6, z: 10.0, a: 1.e+6, b: 1.e+6, c: 1.e+6}"

Set Cartesian maximum path deviation

Default service name

Message type (srv)

Limits

Units

/iiwa/set_cartesian_max_path_deviation

libiiwa_msgs/SetXYZABC

translational: [0.0, Inf), rotational: [0.0, Inf)

translational: m, rotational: radians

Implementation details

# TODO

Example

# abort the motion for a maximum Cartesian path deviation of 0.1 m in the y-axis
$ rosservice call /iiwa/set_cartesian_max_path_deviation "{x: 1.e+6, y: 0.1, z: 1.e+6, a: 1.e+6, b: 1.e+6, c: 1.e+6}"

Cartesian sine impedance control

It will be included in upcoming releases. Open a new discussion if you need to use this functionality ahead of time.