This repository contains support packages that can be used with real KUKA robots as well as with simulations.
kuka_resourcescontains general, common files. It is copied from kuka_experimental and is ported from ROS to ROS2.kuka_cybertech_supportcontains urdf, config and mesh files for KUKA cybertech robots.kuka_kr_moveit_configcontains configuration files for KUKA KR robots necessary for planning with MoveIt.kuka_lbr_iisy_supportcontains urdf, config and mesh files for KUKA iisy robots.kuka_lbr_iisy_moveit_configcontains configuration files for KUKA LBR iisy robots necessary for planning with MoveIt.kuka_agilus_supportcontains urdf, config and mesh files for KUKA Agilus robots, it is copied from kuka_experimental and ported to ROS2.kuka_lbr_iiwa_supportcontains urdf, config and mesh files for KUKA LBR iiwa robotskuka_lbr_iiwa_moveit_configcontains configuration files for KUKA LBR iiwa robots necessary for planning with MoveIt.
All support packages consist of 4 folders:
config: contains joint limits, necessary for time parametrization of trajectorieslaunch: contains launch files to be able to visualize the robot modelsmeshes: contains collision and visual meshes for the robotsurdf: contains the xacro files describing the robots, includingros2_controlintegration (with fake hardware argument)
Each robot has two specific xacro files: a macro ({robot_name}_macro.xacro) and another file instantiating this macro ({robot_name}.urdf.xacro). Additionally there is a xacro providing ros2_control integration, including the name and type of the hardware interface, hardware parameters and the supported state and command interfaces.
Additionally a transmission xacro is provided for gazebo support, but the mechanicalReduction parameters contained within are not valid, only placeholders.
The macro files contain the links and joints of the main serial chain, including transformations, rotation axes, inertial properties, joint position, velocity and effort limits and the location of the mesh files.
The macro file follows the ROS-Industrial conventions:
- link names are
link_{i} - joint names are
joint_{i} - all link and joint names have a
prefixargument - includes
baseframe: equivalent to the base frame defined by the industrial controller ($ROBROOT) - includes
flangeframe: attachment point for EEF models - includes
tool0frame: all-zeros tool frame, identical to the tool frame defined by the industrial controller ($TOOL)
All robots in the xacros are named according to the following pattern:
{kr/lbr_iisy/lbr_iiwa}{payload}_r{reach}_{version},
where version is omitted, if the official product name does not contain it. (e.g. KR 120 R3100-2 is named kr120_r3100_2 and LBR iisy 3 R760 is lbr_iisy3_r760)
The MoveIt configuration packages also contain xacros, that describe the semantic information of the robots: planning groups, default states and link-pairs, for which collision checking should not be done. The default planning group (from base_link to tool0) is named manipulator for all robot arms. An end effector, named end_effector is also defined for all robots, which enables visualising end effector paths in rviz.
To visualise the robot models, the launch files in the launch directory of the support packages can be used. These also start a joint_state_publisher_gui to enable visualisation of the robot meshes and frames with different joint configurations. However they have only visualisation purposes and cannot connect to real or fake hardware.
The frames of the main serial chain in the xacros (base_link to link_6 or link_7) follow the Denavit–Hartenberg conventions of Khalil-Dombre.
The other frames, which are added to conform to ROS-Industrial follow the conventions defined there: base and tool0 are defined to be identical to the frames on the controller, while flange follows REP-103, meaning that in default position x+ points forwards and z+ upwards.
The support packages contain a joint limits file for every supported robot model, necessary time parametrization of MoveIt-planned paths. They contain the velocity limits also available in the URDF model and additional acceleration limits. Acceleration limits can never be global, these values are calculated from the worst-case ramp-up time to reach maximum velocity. The easiest way to modify the allowed velocities and accelerations is to change the velocity and acceleration scaling factors also available in the same configuration files. (The scaling factor can never be smaller than 1.)
In real applications, it's likely that the description will be more complex, involving multiple objects next to the robot and optionally end effectors. It is recommended to create a new, dedicated ROS2 package specifically for managing this extended description by copying and extending the base robot model.
Example of attaching an end effector (with link name eef_base_link) to the flange frame, which could be defined in a different xacro file:
<joint name="${prefix}flange-${prefix}eef" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="${prefix}flange" />
<child link="${prefix}eef_base_link" />
</joint>Some of the data in the xacros might not be valid or missing, the following table shows what can be considered valid.
| Robot name | Robot family | Transformations | Joint position limits | Joint velocity limits | Joint effort limits | Inertial values | Simplified collision meshes |
|---|---|---|---|---|---|---|---|
| lbr_iisy3_r760 | - | ✓ | ✓ | ✓ | ✓ | ✓ | |
| lbr_iisy11_r1300 | - | ✓ | ✓ | ✓ | ✓ | ||
| lbr_iisy15_r930 | - | ✓ | ✓ | ✓ | ✓ | ||
| lbr_iiwa14_r820 | - | ✓ | ✓ | ✓ | |||
| kr6_r700_sixx | agilus | ✓ | ✓ | ✓ | ✓ | ||
| kr6_r900_sixx | agilus | ✓ | ✓ | ✓ | ✓ | ||
| kr10_r1100_2 | agilus | ✓ | ✓ | ✓ | ✓ | ||
| kr16_r2010_2 | cybertech | ✓ | ✓ | ✓ | ✓ | ||
| kr210_r2700_2 | quantec | ✓ | ✓ | ✓ | ✓ | ||
| kr210_r3100_2 | quantec | ✓ | ✓ | ✓ | ✓ |
To start rviz with the motion planning plugin using fake hardware, the following launch files can be used:
ros2 launch kuka_kr_moveit_config moveit_planning_fake_hardware.launch.py
Matching robot_model and robot_family arguments can be added after the command (e.g. robot_model:=kr16_r2010_2 robot_family:=cybertech). The default robot model is kr6_r700_sixx
ros2 launch kuka_lbr_iisy_moveit_config moveit_planning_fake_hardware.launch.py
ros2 launch kuka_lbr_iiwa_moveit_config moveit_planning_fake_hardware.launch.py
A robot_model argument can be added after the command (e.g. robot_model:=lbr_iisy11_r1300). The default robot model is lbr_iisy3_r760
These launch files are not using the actual driver implementation, they only start rviz the move_group server and a ros2_control_node with fake hardware and two controllers joint_state_broadcaster and joint_trajectory_controller The server will be able to accept planning requests from the plugin or from code. (An example how to create such a request from C++ code can be found in the iiqka_moveit_example package in the kuka_drivers repository.) To support hardwares with less performance, the update rate of the control node was reduced to 50 Hz for all robots.