ROS & ROS2: Conditions
Conditions make it possible to monitor the robot control and trigger specific reactions (termination of a running motion) if definable limits are exceeded or not reached
Reset conditions
Reset all conditions
Default service name |
Message type (srv) |
---|---|
|
$ rosservice call /iiwa/reset_conditions "{}"
import rospy
import std_srvs.srv
# wait for service
rospy.wait_for_service('/iiwa/reset_conditions')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/reset_conditions', std_srvs.srv.Empty)
# call service
response = proxy()
$ ros2 service call /iiwa/reset_conditions std_srvs/srv/Empty "{}"
import rclpy
from rclpy.node import Node
import std_srvs.srv
# initialize the ROS node
rclpy.init()
node = Node('test')
# create a client for calling the service
client = node.create_client(std_srvs.srv.Empty, '/iiwa/reset_conditions')
# wait for service
client.wait_for_service()
# call service
request = std_srvs.srv.Empty.Request()
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
# shutdown the node
node.destroy_node()
rclpy.shutdown()
Force conditions
Define the force condition (threshold and tolerance) for each Cartesian axis
Default service name |
Message type (srv) |
Units |
---|---|---|
|
# TODO |
Implementation details
Note
The current implementation links each defined condition by a logic OR operation
# TODO
Example
# thresholds (x: 20.0, y: 21.0, z: 22.0) and tolerances (x: 10.0, y: 11.0, z: 12.0) are specified
$ rosservice call /iiwa/set_force_condition "[20.0, 21.0, 22.0, 10.0, 11.0, 12.0]"
# thresholds (x: 20.0, y: 21.0, z: 22.0) are specified. Default tolerances (10.0)
$ rosservice call /iiwa/set_force_condition "[20.0, 21.0, 22.0]"
# force condition only for z axis: threshold (15.0) and tolerance of (1.0)
$ rosservice call /iiwa/set_force_condition "[.nan, .nan, 15.0, .nan, .nan, 1.0]"
import math
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_force_condition')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_force_condition', libiiwa_msgs.srv.SetArray)
# call service
# thresholds (x: 20.0, y: 21.0, z: 22.0) and tolerances (x: 10.0, y: 11.0, z: 12.0) are specified
response = proxy([20.0, 21.0, 22.0, 10.0, 11.0, 12.0])
# thresholds (x: 20.0, y: 21.0, z: 22.0) are specified. Default tolerances (10.0)
response = proxy([20.0, 21.0, 22.0])
# force condition only for z axis: threshold (15.0) and tolerance of (1.0)
response = proxy([math.nan, math.nan, 15.0, math.nan, math.nan, 1.0])
# thresholds (x: 20.0, y: 21.0, z: 22.0) and tolerances (x: 10.0, y: 11.0, z: 12.0) are specified
$ ros2 service call /iiwa/set_force_condition libiiwa_msgs/srv/SetArray "{data: [20.0, 21.0, 22.0, 10.0, 11.0, 12.0]}"
# thresholds (x: 20.0, y: 21.0, z: 22.0) are specified. Default tolerances (10.0)
$ ros2 service call /iiwa/set_force_condition libiiwa_msgs/srv/SetArray "{data: [20.0, 21.0, 22.0]}"
# force condition only for z axis: threshold (15.0) and tolerance of (1.0)
$ ros2 service call /iiwa/set_force_condition libiiwa_msgs/srv/SetArray "{data: [.nan, .nan, 15.0, .nan, .nan, 1.0]}"
import math
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_force_condition')
# wait for service
client.wait_for_service()
# call service
request = libiiwa_msgs.srv.SetArray.Request()
# thresholds (x: 20.0, y: 21.0, z: 22.0) and tolerances (x: 10.0, y: 11.0, z: 12.0) are specified
request.data = [20.0, 21.0, 22.0, 10.0, 11.0, 12.0]
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
# thresholds (x: 20.0, y: 21.0, z: 22.0) are specified. Default tolerances (10.0)
request.data = [20.0, 21.0, 22.0]
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
# force condition only for z axis: threshold (15.0) and tolerance of (1.0)
request.data = [math.nan, math.nan, 15.0, math.nan, math.nan, 1.0]
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
# shutdown the node
node.destroy_node()
rclpy.shutdown()
Joint torque conditions
Define the joint torque condition (lower and upper limits) for each joint axis
Default service name |
Message type (srv) |
Units |
---|---|---|
|
# TODO |
Implementation details
Note
The current implementation links each defined condition by a logic OR operation
# TODO
Example
# limits for all joints
$ rosservice call /iiwa/set_joint_torque_condition "[-1.0, -2.0, -3.0, -4.0, -5.0, -6.0, -7.0, 1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0]"
# limits only for joint 4 (min: -5.0 Nm, max: 10.0 Nm)
$ rosservice call /iiwa/set_joint_torque_condition "[.nan, .nan, .nan, -5.0, .nan, .nan, .nan, .nan, .nan, .nan, 10.0, .nan, .nan, .nan]"
import math
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_joint_torque_condition')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_joint_torque_condition', libiiwa_msgs.srv.SetArray)
# call service
# limits for all joints
response = proxy([-1.0, -2.0, -3.0, -4.0, -5.0, -6.0, -7.0,
1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0])
# limits only for joint 4 (min: -5.0 Nm, max: 10.0 Nm)
response = proxy([math.nan, math.nan, math.nan, -5.0, math.nan, math.nan, math.nan,
math.nan, math.nan, math.nan, 10.0, math.nan, math.nan, math.nan])
# limits for all joints
$ ros2 service call /iiwa/set_joint_torque_condition libiiwa_msgs/srv/SetArray "{data: [-1.0, -2.0, -3.0, -4.0, -5.0, -6.0, -7.0, 1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0]}"
# limits only for joint 4 (min: -5.0 Nm, max: 10.0 Nm)
$ ros2 service call /iiwa/set_joint_torque_condition libiiwa_msgs/srv/SetArray "{data: [.nan, .nan, .nan, -5.0, .nan, .nan, .nan, .nan, .nan, .nan, 10.0, .nan, .nan, .nan]}"
import math
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_torque_condition')
# wait for service
client.wait_for_service()
# call service
request = libiiwa_msgs.srv.SetArray.Request()
# limits for all joints
request.data = [-1.0, -2.0, -3.0, -4.0, -5.0, -6.0, -7.0,
1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0]
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
# limits only for joint 4 (min: -5.0 Nm, max: 10.0 Nm)
request.data = [math.nan, math.nan, math.nan, -5.0, math.nan, math.nan, math.nan,
math.nan, math.nan, math.nan, 10.0, math.nan, math.nan, math.nan]
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
# shutdown the node
node.destroy_node()
rclpy.shutdown()