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 |
---|---|---|---|
|
[0.0, Inf) |
|
Implementation details
# TODO
Example
$ rosservice call /iiwa/set_joint_stiffness "[400.0, 350.0, 300.0, 250.0, 200.0, 150.0, 100.0]"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_joint_stiffness')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_joint_stiffness', libiiwa_msgs.srv.SetArray)
# call service
response = proxy([400.0, 350.0, 300.0, 250.0, 200.0, 150.0, 100.0])
$ ros2 service call /iiwa/set_joint_stiffness libiiwa_msgs/srv/SetArray "{data: [400.0, 350.0, 300.0, 250.0, 200.0, 150.0, 100.0]}"
import rclpy
from rclpy.node import Node
import libiiwa_msgs.srv
# initialize the ROS node
rclpy.init()
node = Node('test')
# create a client for calling the service
client = node.create_client(libiiwa_msgs.srv.SetArray, '/iiwa/set_joint_stiffness')
# wait for service
client.wait_for_service()
# call service
request = libiiwa_msgs.srv.SetArray.Request()
request.data = [400.0, 350.0, 300.0, 250.0, 200.0, 150.0, 100.0]
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
# shutdown the node
node.destroy_node()
rclpy.shutdown()
Set joint damping
Default service name |
Message type (srv) |
Limits |
Units |
---|---|---|---|
|
[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]"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_joint_damping')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_joint_damping', libiiwa_msgs.srv.SetArray)
# call service
response = proxy([0.7, 0.6, 0.5, 0.4, 0.3, 0.2, 0.1])
$ ros2 service call /iiwa/set_joint_damping libiiwa_msgs/srv/SetArray "{data: [0.7, 0.6, 0.5, 0.4, 0.3, 0.2, 0.1]}"
import rclpy
from rclpy.node import Node
import libiiwa_msgs.srv
# initialize the ROS node
rclpy.init()
node = Node('test')
# create a client for calling the service
client = node.create_client(libiiwa_msgs.srv.SetArray, '/iiwa/set_joint_damping')
# wait for service
client.wait_for_service()
# call service
request = libiiwa_msgs.srv.SetArray.Request()
request.data = [0.7, 0.6, 0.5, 0.4, 0.3, 0.2, 0.1]
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
# shutdown the node
node.destroy_node()
rclpy.shutdown()
Cartesian impedance control
Set Cartesian stiffness
Default service name |
Message type (srv) |
Limits |
Units |
---|---|---|---|
|
translational: [0.0, 5000.0], rotational: [0.0, 300.0], null_space: [0.0, Inf) |
translational: |
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}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_cartesian_stiffness')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_cartesian_stiffness', libiiwa_msgs.srv.SetXYZABCParam)
# call service
response = proxy(x=2000.0, y=3000.0, z=4000.0, a=50.0, b=100.0, c=150.0, float_param=100.0)
# or
request = libiiwa_msgs.srv.SetXYZABCParamRequest()
request.x = 2000.0
request.y = 3000.0
request.z = 4000.0
request.a = 50.0
request.b = 100.0
request.c = 150.0
request.float_param = 100.0
response = proxy(request)
$ ros2 service call /iiwa/set_cartesian_stiffness libiiwa_msgs/srv/SetXYZABCParam "{x: 2000.0, y: 3000.0, z: 4000.0, a: 50.0, b: 100.0, c: 150.0, float_param: 100.0}"
import rclpy
from rclpy.node import Node
import libiiwa_msgs.srv
# initialize the ROS node
rclpy.init()
node = Node('test')
# create a client for calling the service
client = node.create_client(libiiwa_msgs.srv.SetXYZABCParam, '/iiwa/set_cartesian_stiffness')
# wait for service
client.wait_for_service()
# call service
request = libiiwa_msgs.srv.SetXYZABCParam.Request()
request.x = 2000.0
request.y = 3000.0
request.z = 4000.0
request.a = 50.0
request.b = 100.0
request.c = 150.0
request.float_param = 100.0
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
# shutdown the node
node.destroy_node()
rclpy.shutdown()
Set Cartesian damping
Default service name |
Message type (srv) |
Limits |
Units |
---|---|---|---|
|
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}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_cartesian_damping')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_cartesian_damping', libiiwa_msgs.srv.SetXYZABCParam)
# call service
response = proxy(x=0.2, y=0.3, z=0.4, a=0.5, b=0.6, c=0.7, float_param=0.5)
# or
request = libiiwa_msgs.srv.SetXYZABCParamRequest()
request.x = 0.2
request.y = 0.3
request.z = 0.4
request.a = 0.5
request.b = 0.6
request.c = 0.7
request.float_param = 0.5
response = proxy(request)
$ ros2 service call /iiwa/set_cartesian_damping libiiwa_msgs/srv/SetXYZABCParam "{x: 0.2, y: 0.3, z: 0.4, a: 0.5, b: 0.6, c: 0.7, float_param: 0.5}"
import rclpy
from rclpy.node import Node
import libiiwa_msgs.srv
# initialize the ROS node
rclpy.init()
node = Node('test')
# create a client for calling the service
client = node.create_client(libiiwa_msgs.srv.SetXYZABCParam, '/iiwa/set_cartesian_damping')
# wait for service
client.wait_for_service()
# call service
request = libiiwa_msgs.srv.SetXYZABCParam.Request()
request.x = 0.2
request.y = 0.3
request.z = 0.4
request.a = 0.5
request.b = 0.6
request.c = 0.7
request.float_param = 0.5
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
# shutdown the node
node.destroy_node()
rclpy.shutdown()
Set Cartesian additional control force
Default service name |
Message type (srv) |
Limits |
Units |
---|---|---|---|
|
- |
translational: |
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}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_cartesian_additional_control_force')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_cartesian_additional_control_force', libiiwa_msgs.srv.SetXYZABC)
# call service
response = proxy(x=-10.0, y=-20.0, z=-30.0, a=10.0, b=20.0, c=30.0)
# or
request = libiiwa_msgs.srv.SetXYZABCRequest()
request.x = -10.0
request.y = -20.0
request.z = -30.0
request.a = 10.0
request.b = 20.0
request.c = 30.0
response = proxy(request)
$ ros2 service call /iiwa/set_cartesian_additional_control_force libiiwa_msgs/srv/SetXYZABC "{x: -10.0, y: -20.0, z: -30.0, a: 10.0, b: 20.0, c: 30.0}"
import rclpy
from rclpy.node import Node
import libiiwa_msgs.srv
# initialize the ROS node
rclpy.init()
node = Node('test')
# create a client for calling the service
client = node.create_client(libiiwa_msgs.srv.SetXYZABC, '/iiwa/set_cartesian_additional_control_force')
# wait for service
client.wait_for_service()
# call service
request = libiiwa_msgs.srv.SetXYZABC.Request()
request.x = -10.0
request.y = -20.0
request.z = -30.0
request.a = 10.0
request.b = 20.0
request.c = 30.0
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
# shutdown the node
node.destroy_node()
rclpy.shutdown()
Set Cartesian maximum control force
Default service name |
Message type (srv) |
Limits |
Units |
---|---|---|---|
|
translational: [0.0, Inf), rotational: [0.0, Inf) |
translational: |
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}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_cartesian_max_control_force')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_cartesian_max_control_force', libiiwa_msgs.srv.SetXYZABCParam)
# call service
response = proxy(x=10.0, y=20.0, z=30.0, a=10.0, b=20.0, c=30.0, boolean_param=True)
# or
request = libiiwa_msgs.srv.SetXYZABCParamRequest()
request.x = 10.0
request.y = 20.0
request.z = 30.0
request.a = 10.0
request.b = 20.0
request.c = 30.0
request.boolean_param = True
response = proxy(request)
$ ros2 service call /iiwa/set_cartesian_max_control_force libiiwa_msgs/srv/SetXYZABCParam "{x: 10.0, y: 20.0, z: 30.0, a: 10.0, b: 20.0, c: 30.0, boolean_param: true}"
import rclpy
from rclpy.node import Node
import libiiwa_msgs.srv
# initialize the ROS node
rclpy.init()
node = Node('test')
# create a client for calling the service
client = node.create_client(libiiwa_msgs.srv.SetXYZABCParam, '/iiwa/set_cartesian_max_control_force')
# wait for service
client.wait_for_service()
# call service
request = libiiwa_msgs.srv.SetXYZABCParam.Request()
request.x = 10.0
request.y = 20.0
request.z = 30.0
request.a = 10.0
request.b = 20.0
request.c = 30.0
request.boolean_param = True
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
# shutdown the node
node.destroy_node()
rclpy.shutdown()
Set Cartesian maximum velocity
Default service name |
Message type (srv) |
Limits |
Units |
---|---|---|---|
|
translational: [0.0, Inf), rotational: [0.0, Inf) |
translational: |
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}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_cartesian_max_velocity')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_cartesian_max_velocity', libiiwa_msgs.srv.SetXYZABC)
# call service
# abort the motion for a maximum Cartesian velocity of 10 m/s in the z-axis
response = proxy(x=1e6, y=1e6, z=10, a=1e6, b=1e6, c=1e6)
# or
request = libiiwa_msgs.srv.SetXYZABCRequest()
request.x = 1e6
request.y = 1e6
request.z = 10.0
request.a = 1e6
request.b = 1e6
request.c = 1e6
response = proxy(request)
# abort the motion for a maximum Cartesian velocity of 10 m/s in the z-axis
$ ros2 service call /iiwa/set_cartesian_max_velocity libiiwa_msgs/srv/SetXYZABC "{x: 1e6, y: 1e6, z: 10.0, a: 1e6, b: 1e6, c: 1e6}"
import rclpy
from rclpy.node import Node
import libiiwa_msgs.srv
# initialize the ROS node
rclpy.init()
node = Node('test')
# create a client for calling the service
client = node.create_client(libiiwa_msgs.srv.SetXYZABC, '/iiwa/set_cartesian_max_velocity')
# wait for service
client.wait_for_service()
# call service
request = libiiwa_msgs.srv.SetXYZABC.Request()
request.x = 1e6
request.y = 1e6
request.z = 10.0
request.a = 1e6
request.b = 1e6
request.c = 1e6
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
# shutdown the node
node.destroy_node()
rclpy.shutdown()
Set Cartesian maximum path deviation
Default service name |
Message type (srv) |
Limits |
Units |
---|---|---|---|
|
translational: [0.0, Inf), rotational: [0.0, Inf) |
translational: |
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}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_cartesian_max_path_deviation')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_cartesian_max_path_deviation', libiiwa_msgs.srv.SetXYZABC)
# call service
# abort the motion for a maximum Cartesian path deviation of 0.1 m in the y-axis
response = proxy(x=1e6, y=1e6, z=10, a=1e6, b=1e6, c=1e6)
# or
request = libiiwa_msgs.srv.SetXYZABCRequest()
request.x = 1e6
request.y = 0.1
request.z = 1e6
request.a = 1e6
request.b = 1e6
request.c = 1e6
response = proxy(request)
# abort the motion for a maximum Cartesian path deviation of 0.1 m in the y-axis
$ ros2 service call /iiwa/set_cartesian_max_path_deviation libiiwa_msgs/srv/SetXYZABC "{x: 1e6, y: 0.1, z: 1e6, a: 1e6, b: 1e6, c: 1e6}"
import rclpy
from rclpy.node import Node
import libiiwa_msgs.srv
# initialize the ROS node
rclpy.init()
node = Node('test')
# create a client for calling the service
client = node.create_client(libiiwa_msgs.srv.SetXYZABC, '/iiwa/set_cartesian_max_path_deviation')
# wait for service
client.wait_for_service()
# call service
request = libiiwa_msgs.srv.SetXYZABC.Request()
request.x = 1e6
request.y = 0.1
request.z = 1e6
request.a = 1e6
request.b = 1e6
request.c = 1e6
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
# shutdown the node
node.destroy_node()
rclpy.shutdown()
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.