/kuka-lwr

Software related to the KUKA LWR 4+: for real and for simulation.

Primary LanguageC++The UnlicenseUnlicense

KUKA LWR 4+

![In Progress](https://badge.waffle.io/CentroEPiaggio/kuka-lwr.svg?label=in progress&title=in%20progress) ![In Review](https://badge.waffle.io/CentroEPiaggio/kuka-lwr.svg?label=in review&title=in%20review) Build Status

You need help? Press F1 for FAQs, issue your question, or Join the chat at https://gitter.im/CentroEPiaggio/kuka-lwr

Overview

The main packages are:

  • lwr_description: a package that defines the model of the robot (ToDo: name it lwr_model)
  • lwr_hw: a package that contains the LWR 4+ definition within the ros control framework, and also final interfaces using Kuka FRI, Stanford FRI Library or a Gazebo plugin. Read adding an interface below if you wish to add a different non-existing interface.
  • lwr_controllers: a package that implement a set of useful controllers (ToDo: perhaps moving this to a forked version of ros_controllers would be ok, but some controllers are specific for the a 7-dof arm).
  • single_lwr_example: a cofiguration-based meta-package that shows how to use the kuka_lwr packages.
    • single_lwr_robot: the package where you define your robot using the LWR 4+ arm.
    • single_lwr_moveit: the moveit configuration for your single_lwr_robot description.
    • single_lwr_launch: a launch interface to load different components and configuration of your setup be it real, simulation, moveit, visualization, etc.

For an example using two LWR 4+ arms and two Pisa/IIT SoftHands, see the Vito robot.

Adding more interfaces/platforms

The package lwr_hw contains the abstraction that allows to make the most of the new ros control framework. To create an instance of the arm you need to call the function void LWRHW::create(std::string name, std::string urdf_string), where name MUST match the name you give to the xacro instance in the URDF and the urdf_string is any robot description containing one single instance of the lwr called as name (note that, several lwr can exist in urdf_string if they are called differently).

The abstraction is enforced with three pure virtual functions:

  virtual bool init() = 0;
  virtual void read(ros::Time time, ros::Duration period) = 0;
  virtual void write(ros::Time time, ros::Duration period) = 0;

Adding an interface boils down to inherit from the LWRHW class, implement these three function according to your final platform, and creating either a node or a plugin that uses your new class. This way you can use all your planning and controllers setup in any final real or simulated robot.

Examples of final interface class implementations are found for the Kuka FRI, Stanford FRI library and a Gazebo simulation. The corresponding nodes and plugin are found here, here, and here.

How to run a real LWR 4+

  1. Load the script lwr_hw/krl/ros_control.src and the corresponding .dat on the robot.
  2. Place the robot in a position where joints 1 and 3 are as bent as possible (at least 45 degrees) to avoid the "FRI interpolation error" message. A good way to check this is to go into gravity compensation, and see if the robot enters succesfully in that mode with the configured tool.
  3. Set the robot in Position control.
  4. Start the script with the grey and green buttons; the scripts stops at a point and should be started again by releasing and pressing again the green button. You can also use the script in semi-automatic mode.
  5. Start the ROS node, controllers will not start until the handshake is done.
  6. From this point on, you can manage/start/stop/run/switch controllers from ROS, and depending on which interface they use, the switch in the KRC unit is done automatically. Everytime there is a switch of interface, it might take a while to get the controllers running again. If the controllers use the same interface, the switch is done only in ROS, which is faster.

Additional information to use the Stanford FRI Library (not fully tested)

You need to provide your user name with real time priority and memlock limits higher than the default ones. You can do it permanently like this:

  1. sudo nano /etc/security/limits.conf and add these lines:
YOUR_USERNAME hard rtprio 95
YOUR_USERNAME soft rtprio 95
YOUR_USERNAME hard memlock unlimited
YOUR_USERNAME soft memlock unlimited
  1. sudo nano /etc/pam.d/common-session and add session required pam_limits.so
  2. Reboot, open a terminal, and check that ulimit -r -l gives you the values set above.
  3. You need to edit manually the lwr_hw.launch
  4. Load the KRL script that is downloaded with the library to the Robot, and follow the instructions from the original link to set up network and other requirements properly.