ROS & ROS2: Motion and control configuration
Control mode
The KUKA LBR iiwa can be operated with a number of different controllers
Default service name |
Service type (srv) |
Allowed values (case-insensitive) |
---|---|---|
|
|
Example:
$ rosservice call /iiwa/set_control_mode "{data: 'POSITION'}"
# or
$ rosservice call /iiwa/set_control_mode "{data: 'position'}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_control_mode')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_control_mode', libiiwa_msgs.srv.SetString)
# call service
response = proxy("POSITION") # or "position"
print("success:", response.success)
print("message:", response.message)
$ ros2 service call /iiwa/set_control_mode libiiwa_msgs/srv/SetString "{data: 'POSITION'}"
# or
$ ros2 service call /iiwa/set_control_mode libiiwa_msgs/srv/SetString "{data: 'position'}"
import rclpy
from rclpy.node import Node
from libiiwa_msgs.srv import SetString
# initialize the ROS node
rclpy.init()
node = Node('test')
# create a client for calling the service
client = node.create_client(SetString, '/iiwa/set_control_mode')
# wait for service
client.wait_for_service()
# call service
request = SetString.Request()
request.data = "POSITION" # or "position"
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()
Motion type
The KUKA LBR iiwa can programmed to perform different types of motion
Default service name |
Service type (srv) |
Allowed values (case-insensitive) |
---|---|---|
|
|
Example:
$ rosservice call /iiwa/set_motion_type "{data: 'LIN'}"
# or
$ rosservice call /iiwa/set_motion_type "{data: 'lin'}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_motion_type')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_motion_type', libiiwa_msgs.srv.SetString)
# call service
response = proxy("LIN") # or "lin"
print("success:", response.success)
print("message:", response.message)
$ ros2 service call /iiwa/set_motion_type libiiwa_msgs/srv/SetString "{data: 'LIN'}"
# or
$ ros2 service call /iiwa/set_motion_type libiiwa_msgs/srv/SetString "{data: 'lin'}"
import rclpy
from rclpy.node import Node
from libiiwa_msgs.srv import SetString
# initialize the ROS node
rclpy.init()
node = Node('test')
# create a client for calling the service
client = node.create_client(SetString, '/iiwa/set_motion_type')
# wait for service
client.wait_for_service()
# call service
request = SetString.Request()
request.data = "LIN" # or "lin"
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()
Control interface
The KUKA LBR iiwa can be operated with a number of different motion classes
Default service name |
Service type (srv) |
Allowed values (case-insensitive) |
---|---|---|
|
|
Example:
$ rosservice call /iiwa/set_control_interface "{data: 'STANDARD'}"
# or
$ rosservice call /iiwa/set_control_interface "{data: 'standard'}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_control_interface')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_control_interface', libiiwa_msgs.srv.SetString)
# call service
response = proxy("STANDARD") # or "standard"
print("success:", response.success)
print("message:", response.message)
$ ros2 service call /iiwa/set_control_interface libiiwa_msgs/srv/SetString "{data: 'STANDARD'}"
# or
$ ros2 service call /iiwa/set_control_interface libiiwa_msgs/srv/SetString "{data: 'standard'}"
import rclpy
from rclpy.node import Node
from libiiwa_msgs.srv import SetString
# initialize the ROS node
rclpy.init()
node = Node('test')
# create a client for calling the service
client = node.create_client(SetString, '/iiwa/set_control_interface')
# wait for service
client.wait_for_service()
# call service
request = SetString.Request()
request.data = "STANDARD" # or "standard"
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()
Execution type
Motion commands can be executed synchronously or asynchronously
Default service name |
Service type (srv) |
Allowed values (case-insensitive) |
---|---|---|
|
|
Example:
$ rosservice call /iiwa/set_execution_type "{data: 'ASYNCHRONOUS'}"
# or
$ rosservice call /iiwa/set_execution_type "{data: 'asynchronous'}"
import rospy
import libiiwa_msgs.srv
# wait for service
rospy.wait_for_service('/iiwa/set_execution_type')
# create a handle for calling the service
proxy = rospy.ServiceProxy('/iiwa/set_execution_type', libiiwa_msgs.srv.SetString)
# call service
response = proxy("ASYNCHRONOUS") # or "asynchronous"
print("success:", response.success)
print("message:", response.message)
$ ros2 service call /iiwa/set_execution_type libiiwa_msgs/srv/SetString "{data: 'ASYNCHRONOUS'}"
# or
$ ros2 service call /iiwa/set_execution_type libiiwa_msgs/srv/SetString "{data: 'asynchronous'}"
import rclpy
from rclpy.node import Node
from libiiwa_msgs.srv import SetString
# initialize the ROS node
rclpy.init()
node = Node('test')
# create a client for calling the service
client = node.create_client(SetString, '/iiwa/set_execution_type')
# wait for service
client.wait_for_service()
# call service
request = SetString.Request()
request.data = "ASYNCHRONOUS" # or "asynchronous"
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()