ROS & ROS2: Velocities, accelerations and jerk limits
Joint space
Desired relative joint velocity
Define the axis-specific relative velocity (% of maximum velocity)
Default service name |
Service type (srv) |
Limits |
Units |
---|---|---|---|
|
[0, 1] |
unitless |
Example:
$ rosservice call /iiwa/set_desired_joint_velocity_rel "{data: 0.5}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_desired_joint_velocity_rel')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_desired_joint_velocity_rel', libiiwa_msgs.srv.SetNumber)
# call service
response = proxy(0.5)
print("success:", response.success)
print("message:", response.message)
$ ros2 service call /iiwa/set_desired_joint_velocity_rel libiiwa_msgs/srv/SetNumber "{data: 0.5}"
import rclpy
from rclpy.node import Node
from libiiwa_msgs.srv import SetNumber
# initialize the ROS node
rclpy.init()
node = Node('test')
# create a client for calling the service
client = node.create_client(SetNumber, '/iiwa/set_desired_joint_velocity_rel')
# wait for service
client.wait_for_service()
# call service
request = SetNumber.Request()
request.data = 0.5
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
print("success:", response.success)
print("message:", response.message)
# shutdown the node
node.destroy_node()
rclpy.shutdown()
Desired relative joint acceleration
Define the axis-specific relative acceleration (% of maximum acceleration)
Default service name |
Service type (srv) |
Limits |
Units |
---|---|---|---|
|
[0, 1] |
unitless |
Example:
$ rosservice call /iiwa/set_desired_joint_acceleration_rel "{data: 0.5}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_desired_joint_acceleration_rel')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_desired_joint_acceleration_rel', libiiwa_msgs.srv.SetNumber)
# call service
response = proxy(0.5)
print("success:", response.success)
print("message:", response.message)
$ ros2 service call /iiwa/set_desired_joint_acceleration_rel libiiwa_msgs/srv/SetNumber "{data: 0.5}"
import rclpy
from rclpy.node import Node
from libiiwa_msgs.srv import SetNumber
# initialize the ROS node
rclpy.init()
node = Node('test')
# create a client for calling the service
client = node.create_client(SetNumber, '/iiwa/set_desired_joint_acceleration_rel')
# wait for service
client.wait_for_service()
# call service
request = SetNumber.Request()
request.data = 0.5
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
print("success:", response.success)
print("message:", response.message)
# shutdown the node
node.destroy_node()
rclpy.shutdown()
Desired relative joint jerk
Define the axis-specific relative jerk (% of maximum jerk)
Default service name |
Service type (srv) |
Limits |
Units |
---|---|---|---|
|
[0, 1] |
unitless |
Example:
$ rosservice call /iiwa/set_desired_joint_jerk_rel "{data: 0.5}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_desired_joint_jerk_rel')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_desired_joint_jerk_rel', libiiwa_msgs.srv.SetNumber)
# call service
response = proxy(0.5)
print("success:", response.success)
print("message:", response.message)
$ ros2 service call /iiwa/set_desired_joint_jerk_rel libiiwa_msgs/srv/SetNumber "{data: 0.5}"
import rclpy
from rclpy.node import Node
from libiiwa_msgs.srv import SetNumber
# initialize the ROS node
rclpy.init()
node = Node('test')
# create a client for calling the service
client = node.create_client(SetNumber, '/iiwa/set_desired_joint_jerk_rel')
# wait for service
client.wait_for_service()
# call service
request = SetNumber.Request()
request.data = 0.5
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
print("success:", response.success)
print("message:", response.message)
# shutdown the node
node.destroy_node()
rclpy.shutdown()
Cartesian space
Desired Cartesian velocity
Define the absolute Cartesian velocity
Default service name |
Service type (srv) |
Limits |
Units |
---|---|---|---|
|
(0, Inf) |
\(m/s\) |
Example:
$ rosservice call /iiwa/set_desired_cartesian_velocity "{data: 0.25}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_desired_cartesian_velocity')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_desired_cartesian_velocity', libiiwa_msgs.srv.SetNumber)
# call service
response = proxy(0.25)
print("success:", response.success)
print("message:", response.message)
$ ros2 service call /iiwa/set_desired_cartesian_velocity libiiwa_msgs/srv/SetNumber "{data: 0.25}"
import rclpy
from rclpy.node import Node
from libiiwa_msgs.srv import SetNumber
# initialize the ROS node
rclpy.init()
node = Node('test')
# create a client for calling the service
client = node.create_client(SetNumber, '/iiwa/set_desired_cartesian_velocity')
# wait for service
client.wait_for_service()
# call service
request = SetNumber.Request()
request.data = 0.25
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
print("success:", response.success)
print("message:", response.message)
# shutdown the node
node.destroy_node()
rclpy.shutdown()
Desired Cartesian acceleration
Define the absolute Cartesian acceleration
Default service name |
Service type (srv) |
Limits |
Units |
---|---|---|---|
|
(0, Inf) |
\(m/s^2\) |
Example:
$ rosservice call /iiwa/set_desired_cartesian_acceleration "{data: 0.25}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_desired_cartesian_acceleration')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_desired_cartesian_acceleration', libiiwa_msgs.srv.SetNumber)
# call service
response = proxy(0.25)
print("success:", response.success)
print("message:", response.message)
$ ros2 service call /iiwa/set_desired_cartesian_acceleration libiiwa_msgs/srv/SetNumber "{data: 0.25}"
import rclpy
from rclpy.node import Node
from libiiwa_msgs.srv import SetNumber
# initialize the ROS node
rclpy.init()
node = Node('test')
# create a client for calling the service
client = node.create_client(SetNumber, '/iiwa/set_desired_cartesian_acceleration')
# wait for service
client.wait_for_service()
# call service
request = SetNumber.Request()
request.data = 0.25
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
print("success:", response.success)
print("message:", response.message)
# shutdown the node
node.destroy_node()
rclpy.shutdown()
Desired Cartesian jerk
Define the absolute Cartesian jerk
Default service name |
Service type (srv) |
Limits |
Units |
---|---|---|---|
|
(0, Inf) |
\(m/s^3\) |
Example:
$ rosservice call /iiwa/set_desired_cartesian_jerk "{data: 0.25}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_desired_cartesian_jerk')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_desired_cartesian_jerk', libiiwa_msgs.srv.SetNumber)
# call service
response = proxy(0.25)
print("success:", response.success)
print("message:", response.message)
$ ros2 service call /iiwa/set_desired_cartesian_jerk libiiwa_msgs/srv/SetNumber "{data: 0.25}"
import rclpy
from rclpy.node import Node
from libiiwa_msgs.srv import SetNumber
# initialize the ROS node
rclpy.init()
node = Node('test')
# create a client for calling the service
client = node.create_client(SetNumber, '/iiwa/set_desired_cartesian_jerk')
# wait for service
client.wait_for_service()
# call service
request = SetNumber.Request()
request.data = 0.25
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
response = future.result()
print("success:", response.success)
print("message:", response.message)
# shutdown the node
node.destroy_node()
rclpy.shutdown()