ROS & ROS2
ROS/ROS2 node
Launching the node
For a single robot (with the default configuration) simply launch:
$ roslaunch libiiwa_ros default.launch
For multiple robots in the same ROS environment it is necessary to define different communication ports and namespaces for each one as follows:
The port (
libiiwa_port
) must be unique and must also be defined on each robot’s Sunrise project (Controller: Port
, editable on the smartHMI).Namespace (
__ns
) will prefix each topic and service name to avoid naming conflicts.
$ roslaunch libiiwa_ros default.launch libiiwa_port:=12225 __ns:=robot1
$ roslaunch libiiwa_ros default.launch libiiwa_port:=12226 __ns:=robot2
For a single robot (with the default configuration) simply launch:
$ ros2 launch libiiwa_ros2 default.py
For multiple robots in the same ROS environment it is necessary to define different communication ports and namespaces for each one as follows:
The port (
libiiwa_port
) must be unique and must also be defined on each robot’s Sunrise project (Controller: Port
, editable on the smartHMI).Namespace (
__ns
) will prefix each topic and service name to avoid naming conflicts.
$ ros2 launch libiiwa_ros2 default.py libiiwa_port:=12225 __ns:=robot1
$ ros2 launch libiiwa_ros2 default.py libiiwa_port:=12226 __ns:=robot2
Note
After launching the node, program execution is blocked until the Java library installed in the KUKA Sunrise Cabinet is executed via the smartHMI.
Launch parameters
Launch parameter |
Description |
Type |
Default value |
---|---|---|---|
|
IP address of the library communication endpoint (default: all interfaces) |
|
|
|
Port of the library communication endpoint |
|
|
|
Whether to enable the servo interface at node startup |
|
|
|
Whether to print additional information |
|
|
Note
Visit MoveIt support for the FollowJointTrajectory
actionlib configuration
Launch file: libiiwa_ros/launch/default.launch
<launch>
<!-- FollowJointTrajectory action: /controller_name/action_namespace -->
<arg name="controller_name" default="iiwa_controller"/>
<arg name="action_namespace" default="follow_joint_trajectory"/>
<arg name="follow_all_trajectory" default="true"/>
<arg name="trajectory_update_threshold" default="0.5"/>
<!-- libiiwa configuration (see LibIiwa class) -->
<arg name="libiiwa_ip" default="0.0.0.0"/>
<arg name="libiiwa_port" default="12225"/>
<arg name="servo_interface" default="true"/>
<!-- node configuration -->
<arg name="verbose" default="false"/>
<!-- launch ROS node -->
<node name="libiiwa_ros" pkg="libiiwa_ros" type="node.py" output="screen" cwd="node">
<param name="controller_name" type="str" value="$(arg controller_name)"/>
<param name="action_namespace" type="str" value="$(arg action_namespace)"/>
<param name="follow_all_trajectory" type="bool" value="$(arg follow_all_trajectory)"/>
<param name="trajectory_update_threshold" type="double" value="$(arg trajectory_update_threshold)"/>
<param name="libiiwa_ip" type="str" value="$(arg libiiwa_ip)"/>
<param name="libiiwa_port" type="int" value="$(arg libiiwa_port)"/>
<param name="servo_interface" type="bool" value="$(arg servo_interface)"/>
<param name="verbose" type="bool" value="$(arg verbose)"/>
</node>
</launch>
Launch file: libiiwa_ros2/launch/default.py
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import TextSubstitution
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
def generate_launch_description():
namespace_launch_arg = DeclareLaunchArgument(
"__ns", default_value=TextSubstitution(text="/")
)
# FollowJointTrajectory action: /controller_name/action_namespace
controller_name_launch_arg = DeclareLaunchArgument(
"controller_name", default_value=TextSubstitution(text="iiwa_controller")
)
action_namespace_launch_arg = DeclareLaunchArgument(
"action_namespace", default_value=TextSubstitution(text="follow_joint_trajectory")
)
follow_all_trajectory_launch_arg = DeclareLaunchArgument(
"follow_all_trajectory", default_value=TextSubstitution(text="True")
)
trajectory_update_threshold_launch_arg = DeclareLaunchArgument(
"trajectory_update_threshold", default_value=TextSubstitution(text="0.5")
)
# libiiwa configuration (see LibIiwa class)
libiiwa_ip_launch_arg = DeclareLaunchArgument(
"libiiwa_ip", default_value=TextSubstitution(text="0.0.0.0")
)
libiiwa_port_launch_arg = DeclareLaunchArgument(
"libiiwa_port", default_value=TextSubstitution(text="12225")
)
servo_interface_launch_arg = DeclareLaunchArgument(
"servo_interface", default_value=TextSubstitution(text="True")
)
# node configuration
verbose_launch_arg = DeclareLaunchArgument(
"verbose", default_value=TextSubstitution(text="False")
)
# ROS2 node
node = Node(
package='libiiwa_ros2',
namespace=LaunchConfiguration('__ns'),
executable='node',
name='iiwa',
parameters=[{
"__ns": LaunchConfiguration('__ns'),
"controller_name": LaunchConfiguration('controller_name'),
"action_namespace": LaunchConfiguration('action_namespace'),
"follow_all_trajectory": LaunchConfiguration('follow_all_trajectory'),
"trajectory_update_threshold": LaunchConfiguration('trajectory_update_threshold'),
"libiiwa_ip": LaunchConfiguration('libiiwa_ip'),
"libiiwa_port": LaunchConfiguration('libiiwa_port'),
"servo_interface": LaunchConfiguration('servo_interface'),
"verbose": LaunchConfiguration('verbose')
}],
output='screen',
)
return LaunchDescription([
namespace_launch_arg,
controller_name_launch_arg,
action_namespace_launch_arg,
follow_all_trajectory_launch_arg,
trajectory_update_threshold_launch_arg,
libiiwa_ip_launch_arg,
libiiwa_port_launch_arg,
servo_interface_launch_arg,
verbose_launch_arg,
node
])
ROS/ROS2 messages
Services
GetBool.srv
---
bool data # e.g. if it's ready to move
GetError.srv
---
int32 error_code
int32 NO_ERROR=-10
int32 VALUE_ERROR=-11
int32 INVALID_JOINT_ERROR=-12
int32 SYNCHRONOUS_MOTION_ERROR=-13
int32 ASYNCHRONOUS_MOTION_ERROR=-14
int32 VALIDATION_FOR_IMPEDANCE_ERROR=-15
int32 INVALID_CONFIGURATION_ERROR=-16
GetNumber.srv
---
float64 data # e.g. for time to destination
SetArray.srv
float64[] data
---
bool success # indicate successful run of triggered service
string message # informational, e.g. for error messages
SetNumber.srv
float64 data # e.g. for desired velocity
---
bool success # indicate successful run of triggered service
string message # informational, e.g. for error messages
SetString.srv
string data # e.g. for configuration modes
---
bool success # indicate successful run of triggered service
string message # informational, e.g. for error messages
SetXYZABC.srv
float64 x # e.g. Cartesian x coordinate
float64 y # e.g. Cartesian y coordinate
float64 z # e.g. Cartesian z coordinate
float64 a # e.g. Cartesian orientation alpha angle
float64 b # e.g. Cartesian orientation beta angle
float64 c # e.g. Cartesian orientation gamma angle
---
bool success # indicate successful run of triggered service
string message # informational, e.g. for error messages
SetXYZABCParam.srv
float64 x # e.g. Cartesian x coordinate
float64 y # e.g. Cartesian y coordinate
float64 z # e.g. Cartesian z coordinate
float64 a # e.g. Cartesian orientation alpha angle
float64 b # e.g. Cartesian orientation beta angle
float64 c # e.g. Cartesian orientation gamma angle
bool boolean_param # boolean parameter
float64 float_param # float parameter. E.g. null_space value
---
bool success # indicate successful run of triggered service
string message # informational, e.g. for error messages