The package ipa_kuka_rsi implements a ROS driver for the Kuka RSI XML protocol to control joint and cartesian movements.

Example launch file

An example to start the driver is given by:

roslaunch ipa_kuka_rsi test_driver.launch

Configuration on KR16

To enable the arm to communicate with ROS driver the machting KUKA Robot Language script has to be started. All necessary files are stored in "common/KUKA". Copy the configuraiton files:

to "C:\KRC\Roboter\Config\User\Common\SensorInterface" on your KR16 arm. Use "RSI_UniversalEthernet.src" to start the script on the arm which uses the other configuration files and enables RSI communication.

How to use the driver?

Please refer to the test scripts in "ros/test". The test scripts are simple examples of the joint or cartesian control with the action server.

ROS API

The ipa_kuka_rsi package provides both, a joint based and a cartesian movement.

Subscribed Topics

joint_command (trajectory_msgs/JointTrajectoryPoint)
  • Receives single joint command.
joint_path_command (trajectory_msgs/JointTrajectory)
  • Receives a trajectory.

Published Topics

diagnostics (diagnostic_msgs/DiagnosticArray)
  • Publishes diagnostics messages of the arm.
joint_states (sensor_msgs/JointState)
  • Publishes the joint states of the arm in rad.

Services

init (cob_srvs/Trigger)
  • Initializes RSI connection.
recover (cob_srvs/Trigger)
  • Recovers RSI connection (not implemented).
motion_mode (cob_srvs/SetOperationMode)
  • Switches between cartesian and joint based movement.

Parameters

~initialized (bool, default: false)
  • If set to true, the driver initializes automatically (testing purpose).
~frequency (int, default: 30)
  • Frequency to publish joint states and diagnostics, as well as for controller.
~joint_names (list of strings)
  • A list of names for each joint.
~joint_limits (list of of list of float)
  • Max. and min. limits for each joint in rad, e.g. [ [-1,1], [-2,2] ]
~tolerance (list of float)
  • Tolerance in rad when goal counts as reached
~max_velocity (float, default: 0.1)
  • Max. velocity for joint movement
~RSI_joint_name (string, default: ASPos)
  • Name of the RSI property for setting joint angles.
~RSI_cart_name (string, default: RSol)
  • Name of the RSI property for setting cart. pose.
~tip_link (string)
  • Link name of tip of the arm
~base_link_ (string)
  • Link name of the base of the arm
~config (string, default: 1)
  • Filename of the ERC configuration file which is shared between driver and Kuka arm.
~mode_motion (string, default: joint)
  • Sets the desired motion mode at startup. Possible values are: joint, cartesian

Required tf Transforms

~base_link"frame_id of goal"
  • description of transform

Action API

The ipa_kuka_rsi node provides an implementation of two SimpleActionServer (see actionlib documentation), for movement of joint based trajectories or cartesian trajectories.

Action Subscribed Topics

follow_joint_trajectory/goal (control_msgs/FollowJointTrajectoryActionGoal)

  • Follow a trajectory (joint).
move_cartesian/goal (moveit_msgs/MoveGroupActionGoal)
  • Move to a pose (cart.) by filling in the goal constraint of position and orientation with a correct link_name (same as tip_link).

Action Published Topics

follow_joint_trajectory/feedback (control_msgs/FollowJointTrajectoryActionFeedback)

  • Feedback contains the current joint position and error to the desired joint position in rad.
follow_joint_trajectory/result (control_msgs/FollowJointTrajectoryActionResult)
  • Result of the movement.
move_cartesian/result (moveit_msgs/MoveGroupActionResult)
  • Result of the movement.

Dynamic Reconfigure

Some parameters such as frequency, motion mode and more can be configured by dynamic reconfigure.

How to use the RSI communication layer for your own software

   1 #include <ipa_kuka_rsi/rsi_server.h>
   2 
   3 RSI::RSI_Server rsi("filename to ERC configuration");
   4 
   5 if(rsi.received_something())
   6   ROS_INFO("connection established!");
   7 
   8 double value;
   9 //the method checks the variable type and existence!
  10 bool found = rsi.get("SomeNameFromERC", value);
  11 if(!found)
  12   ROS_INFO("could not read the variable");
  13 
  14 //the method checks the variable type and existence!
  15 bool ok = rsi.set("SomeNameFromERC", 42.37);
  16 if(!ok)
  17   ROS_INFO("could not set the variable");

Wiki: ipa_kuka_rsi (last edited 2014-09-10 11:48:00 by josh)