ROS & ROS2


ROS/ROS2 node

Launching the node

For a single robot (with the default configuration) simply launch:

$ roslaunch libiiwa_ros default.launch

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 parameters

Launch parameter

Description

Type

Default value

libiiwa_ip

IP address of the library communication endpoint (default: all interfaces)

str

"0.0.0.0"

libiiwa_port

Port of the library communication endpoint

int

12225

servo_interface

Whether to enable the servo interface at node startup

bool

true

verbose

Whether to print additional information

bool

false

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>

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