Note: This tutorial assumes that you have completed the previous introductory tutorials. If you want to create an IK plugin for ROS, you should have completed the arm navigation tutorial.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Create a kinematics solution using IK Fast

Description: This tutorial describes how to automatically create a fast, closed-form analytical kinematics solution for your robot using the IKFast module from OpenRAVE.

Tutorial Level: INTERMEDIATE

A new version of the IKFast Generator streamlined for Catkin and MoveIt! is documented here. It is recommended to use that version. This page is kept for archival purposes.

Background

By following the earlier tutorials, you should have created an arm navigation package for your robot using the wizard. This will have configured the planning system to use the default KDL kinematics plugin, which finds IK solutions using a numerical method. By creating a new plugin using IKFast, IK solutions can be found much... faster!

As of writing, OpenRAVE 0.8.* includes IKFast61, however the the plugin generator is backwards compatible and has been tested with IKFast54/56/61.
You don't need to actually install OpenRAVE because we only need to use the IKFast python scripts.

Performance results, average time to generate solution for 6 DOF manipulator:
IKFast54: unknown
IKFast56: 430 ms
IKFast61: 10 ms
however it is reported to work in nanoseconds. Please report back with your own test results?

A good example of a robot using IKFast in ROS is the Motoman SIA10D.
To run the simulated planning system on ROS Fuerte:

$ sudo aptitude install ros-fuerte-industrial
$ roslaunch sia10d_mesh_arm_navigation planning_scene_warehouse_viewer_sia10d_mesh.launch 

For more information, see this tutorial:
http://www.ros.org/wiki/motoman/Tutorials/Path_Planning_with_Arm_Warehouse_Viewer http://img.acianetmedia.com/i/Vljwc.png

You can also use the generated IK code directly in your own projects.

This tutorial was tested with Ubuntu 11.10 (Oneiric) and ROS Fuerte.
Updated: Nov 2012

Install Prerequisites

Follow these instructions to install the IKFast IK-generation scripts and other required prerequisites.

Depending on the installation method used, the path to ikfast.py may differ. This tutorial uses <openravepy> to refer to the ikfast.py installation directory.

  • source install: openrave-0.8.2-src/python

  • package install: /usr/lib/python2.7/dist-packages/openravepy/_openravepy_0_8

Create robot model

The IKFast routine requires a model of the robot in either OpenRAVE's custom XML format or a Collada DAE format.

Converting from URDF

For many robots, it may be easiest to convert an existing URDF model into the Collada format:

  1. If your model is in xacro format, convert it to pure URDF:
    $ rosrun xacro xacro.py my_robot.urdf.xacro > my_robot.urdf
  2. Convert URDF to collada format:
    $ rosrun collada_urdf urdf_to_collada my_robot.urdf my_robot.dae

Here are some troubleshooting tips, if you're having trouble with the conversion:

  • you may have to remove any visual/collision geometry using boxes, which can't be automatically converted to collada.
  • Warning messages involving geometry can be ignored, since ikfast only requires the frame transforms.
  • urdf_to_collada produces a Segmentation Fault under groovy. You'll need to run this conversion under fuerte, for now.

Verifying a Collada model

If you installed the full version of OpenRAVE, you can view your model:

$ openrave my_robot.dae

Alternatively you can load the Collada model back into rviz using the orrosplanning package from the openrave_planning stack:

$ cd ~/ros_workspace
$ mkdir openrave_planning
$ cd openrave_planning
$ svn co https://jsk-ros-pkg.svn.sourceforge.net/svnroot/jsk-ros-pkg/trunk/openrave_planning/orrosplanning/ orrosplanning/
$ export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:~/ros_workspace/openrave_planning
$ rosmake orrosplanning

$ roslaunch orrosplanning collada_rviz_display.launch model:=my_robot.dae

Generate the IK solution

Select IK Type

You need to choose which sort of IK you want. See this page for more info. The most common IK type is "transform6d".

You also need the link index numbers for the base_link and end_link between which the IK will be calculated. You can count the number of links by checking in the .dae file. Alternatively, if you have OpenRAVE installed you can view a list of links in your model:

$ openrave-robot.py my_robot.dae --info links

NOTE: use openrave0.8-robot.py if installed from packages

A typical 6-DOF manipulator should have 6 arm links + a dummy base_link as required by ROS specifications. If no extra links are present in the model, this gives: baselink=0 and eelink=6. Often, an additional tool_link will be provided to position the grasp/tool frame, giving eelink=7.

The manipulator shown below also has another dummy mounting_link, giving baselink=1 and eelink=8.

name           index parents      
---------------------------------
base_link      0                  
mounting_link  1     base_link    
link1_rotate   2     mounting_link
link2          3     link1_rotate
link3          4     link2
link4          5     link3    
link5          6     link4    
link6_wrist    7     link5   
tool_link      8     link6_wrist   
---------------------------------

Generate IK Solver

Generate the IK, between the manipulator's base and tool frames:

$ python <openravepy>/ikfast.py --robot=my_robot.dae --iktype=transform6d --baselink=1 --eelink=8 --savefile=output_ikfast61.cpp

The speed and success of this process will depend on the complexity of your robot.
A typical 6 DOF manipulator with 3 intersecting axis at the base or wrist will take only a few minutes to generate the IK.
You should consult the OpenRAVE mailing list and ROS Answers for information about 5 and 7 DOF manipulators. You can specify the 7th link be free, using the --freeindex= parameter.

Testing output from IKFast

To test the forward and inverse kinematics results, download this demo code:
http://kaist-ros-pkg.googlecode.com/svn/trunk/arm_kinematics_tools/src/ikfastdemo/ikfastdemo.cpp

Copy the source file to the same directory as the output files from IKFast.
Edit ikfastdemo.cpp and define IK_VERSION with the version of IKFast you used.
Make sure the #include line points to the output file from IKFast.

#define IK_VERSION 61
#include "output_ikfast61.cpp"

Compile the program:

g++ ikfastdemo.cpp -lstdc++ -llapack -o compute -lrt

(If you get an error, you can try changing the order of the filename/arguments to g++. You may need to include openravepy. You may need to install the lapack library.)

g++ ikfastdemo.cpp -lstdc++ -llapack -o compute -lrt -I<openravepy>

Run the program to check the correct usage:

./compute

You can compute the forward kinematics by specifying all joint angles. Inverse kinematics can be found from either a translation-quaternion or translation-rotation matrix pose. Kinematics can also be verified visually after creating a plugin (below), using the planning-scene environment.

Create IKFast plugin

To use the new IK solver in ROS planning and navigation packages, you must create a plugin that implements a standard ROS interface. The creation and testing of this plugin is different, depending on whether you are using arm_navigation or moveIt!:

Wiki: Industrial/Tutorials/Create_a_Fast_IK_Solution (last edited 2015-10-21 09:34:57 by VictorLamoine)