ROS & ROS2: State and errors
Robot state
Joint positions, velocities and torques (effort)
Read the axis-specific (joint) actual positions, velocities (internally calculated as the position difference in 1/100 second interval) and external acting torques (without the component resulting from the robot weight and mass inertias during motion)
Default topic name |
Message type (msg) |
Units |
---|---|---|
|
position (\(radians\)), velocity (\(radians/s\)), torque (\(Nm\)) |
$ rostopic echo /iiwa/state/joint_states
import rospy
import sensor_msgs.msg
# subscription callback
def callback(msg):
print("positions:", msg.position)
print("velocities:", msg.velocity)
print("torques:", msg.effort)
# subscribe to topic
rospy.Subscriber('/iiwa/state/joint_states', sensor_msgs.msg.JointState, callback)
# initialize the ROS node
rospy.init_node('test')
rospy.spin()
$ ros2 topic echo /iiwa/state/joint_states
import rclpy
import sensor_msgs.msg
from rclpy.node import Node
from rclpy.qos import QoSPresetProfiles
# subscription callback
def callback(msg):
print("positions:", msg.position)
print("velocities:", msg.velocity)
print("torques:", msg.effort)
# initialize the ROS node
rclpy.init()
node = Node('test')
# create subscription
node.create_subscription(msg_type=sensor_msgs.msg.JointState,
topic='/iiwa/state/joint_states',
callback=callback,
qos_profile=QoSPresetProfiles.SYSTEM_DEFAULT.value)
try:
rclpy.spin_once(node)
except KeyboardInterrupt:
pass
finally:
# shutdown the node
node.destroy_node()
rclpy.shutdown()
End-effector Cartesian pose (position and orientation)
Read the end-effector Cartesian position (X,Y,Z) and orientation (A,B,C)
Default topic name |
Message type (msg) |
Units |
---|---|---|
|
position (\(m\)), orientation as quaternion |
$ rostopic echo /iiwa/state/end_effector_pose
import rospy
import geometry_msgs.msg
# subscription callback
def callback(msg):
print("position:", msg.position)
print("orientation (quaternion):", msg.orientation)
# subscribe to topic
rospy.Subscriber('/iiwa/state/end_effector_pose', geometry_msgs.msg.Pose, callback)
# initialize the ROS node
rospy.init_node('test')
rospy.spin()
$ ros2 topic echo /iiwa/state/end_effector_pose
import rclpy
import geometry_msgs.msg
from rclpy.node import Node
from rclpy.qos import QoSPresetProfiles
# subscription callback
def callback(msg):
print("position:", msg.position)
print("orientation (quaternion):", msg.orientation)
# initialize the ROS node
rclpy.init()
node = Node('test')
# create subscription
node.create_subscription(msg_type=geometry_msgs.msg.Pose,
topic='/iiwa/state/end_effector_pose',
callback=callback,
qos_profile=QoSPresetProfiles.SYSTEM_DEFAULT.value)
try:
rclpy.spin_once(node)
except KeyboardInterrupt:
pass
finally:
# shutdown the node
node.destroy_node()
rclpy.shutdown()
End-effector Cartesian forces and torques
Read the end-effector Cartesian force (X,Y,Z) and torque (A,B,C)
Default topic name |
Message type (msg) |
Units |
---|---|---|
|
force (\(N\)), torque (\(Nm\)) |
$ rostopic echo /iiwa/state/end_effector_wrench
import rospy
import geometry_msgs.msg
# subscription callback
def callback(msg):
print("force:", msg.force)
print("torque:", msg.torque)
# subscribe to topic
rospy.Subscriber('/iiwa/state/end_effector_wrench', geometry_msgs.msg.Wrench, callback)
# initialize the ROS node
rospy.init_node('test')
rospy.spin()
$ ros2 topic echo /iiwa/state/end_effector_wrench
import rclpy
import geometry_msgs.msg
from rclpy.node import Node
from rclpy.qos import QoSPresetProfiles
# subscription callback
def callback(msg):
print("force:", msg.force)
print("torque:", msg.torque)
# initialize the ROS node
rclpy.init()
node = Node('test')
# create subscription
node.create_subscription(msg_type=geometry_msgs.msg.Wrench,
topic='/iiwa/state/end_effector_wrench',
callback=callback,
qos_profile=QoSPresetProfiles.SYSTEM_DEFAULT.value)
try:
rclpy.spin_once(node)
except KeyboardInterrupt:
pass
finally:
# shutdown the node
node.destroy_node()
rclpy.shutdown()
Has fired condition
Whether motion has terminated due to a break condition
Default service name |
Service type (srv) |
---|---|
|
$ rosservice call /iiwa/has_fired_condition "{}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/has_fired_condition')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/has_fired_condition', libiiwa_msgs.srv.GetBool)
# call service
response = proxy()
print("has fired condition:", response.data)
$ ros2 service call /iiwa/has_fired_condition libiiwa_msgs/srv/GetBool "{}"
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.GetBool, '/iiwa/has_fired_condition')
# wait for service
client.wait_for_service()
# call service
request = libiiwa_msgs.srv.GetBool.Request()
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
print("data:", response.data)
# shutdown the node
node.destroy_node()
rclpy.shutdown()
Is ready to move
Whether the robot is ready for motion. A true value does not necessarily mean that the brakes are open and that the robot is under servo control
Default service name |
Service type (srv) |
---|---|
|
$ rosservice call /iiwa/is_ready_to_move "{}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/is_ready_to_move')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/is_ready_to_move', libiiwa_msgs.srv.GetBool)
# call service
response = proxy()
print("is ready to move:", response.data)
$ ros2 service call /iiwa/is_ready_to_move libiiwa_msgs/srv/GetBool "{}"
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.GetBool, '/iiwa/is_ready_to_move')
# wait for service
client.wait_for_service()
# call service
request = libiiwa_msgs.srv.GetBool.Request()
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
print("data:", response.data)
# shutdown the node
node.destroy_node()
rclpy.shutdown()
Has active motion
Whether the robot is active. It does not provide any information on whether the robot is currently in motion (a false value does not necessarily mean that the robot is stationary)
Default service name |
Service type (srv) |
---|---|
|
$ rosservice call /iiwa/has_active_motion "{}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/has_active_motion')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/has_active_motion', libiiwa_msgs.srv.GetBool)
# call service
response = proxy()
print("has active motion:", response.data)
$ ros2 service call /iiwa/has_active_motion libiiwa_msgs/srv/GetBool "{}"
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.GetBool, '/iiwa/has_active_motion')
# wait for service
client.wait_for_service()
# call service
request = libiiwa_msgs.srv.GetBool.Request()
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
print("data:", response.data)
# shutdown the node
node.destroy_node()
rclpy.shutdown()
Errors
Last registered error code
Default service name |
Service type (srv) |
---|---|
|
$ rosservice call /iiwa/last_error "{}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/last_error')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/last_error', libiiwa_msgs.srv.GetError)
# call service
response = proxy()
print("error code:", response.error_code)
# compare with default error codes
response.error_code == libiiwa_msgs.srv.GetErrorResponse.NO_ERROR
response.error_code == libiiwa_msgs.srv.GetErrorResponse.VALUE_ERROR
response.error_code == libiiwa_msgs.srv.GetErrorResponse.INVALID_JOINT_ERROR
response.error_code == libiiwa_msgs.srv.GetErrorResponse.SYNCHRONOUS_MOTION_ERROR
response.error_code == libiiwa_msgs.srv.GetErrorResponse.ASYNCHRONOUS_MOTION_ERROR
response.error_code == libiiwa_msgs.srv.GetErrorResponse.VALIDATION_FOR_IMPEDANCE_ERROR
response.error_code == libiiwa_msgs.srv.GetErrorResponse.INVALID_CONFIGURATION_ERROR
$ ros2 service call /iiwa/last_error libiiwa_msgs/srv/GetError "{}"
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.GetError, '/iiwa/last_error')
# wait for service
client.wait_for_service()
# call service
request = libiiwa_msgs.srv.GetError.Request()
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
print("error_code:", response.error_code)
# compare with default error codes
response.error_code == libiiwa_msgs.srv.GetError.Response.NO_ERROR
response.error_code == libiiwa_msgs.srv.GetError.Response.VALUE_ERROR
response.error_code == libiiwa_msgs.srv.GetError.Response.INVALID_JOINT_ERROR
response.error_code == libiiwa_msgs.srv.GetError.Response.SYNCHRONOUS_MOTION_ERROR
response.error_code == libiiwa_msgs.srv.GetError.Response.ASYNCHRONOUS_MOTION_ERROR
response.error_code == libiiwa_msgs.srv.GetError.Response.VALIDATION_FOR_IMPEDANCE_ERROR
response.error_code == libiiwa_msgs.srv.GetError.Response.INVALID_CONFIGURATION_ERROR
# shutdown the node
node.destroy_node()
rclpy.shutdown()