Generate IKFast Plugin Tutorial

In this section, we will walk through configuring an IKFast plugin for MoveIt!

What is IKFast?

From Wikipedia: IKFast, the Robot Kinematics Compiler, is a powerful inverse kinematics solver provided within Rosen Diankov’s OpenRAVE motion planning software. Unlike most inverse kinematics solvers, IKFast can analytically solve the kinematics equations of any complex kinematics chain, and generate language-specific files (like C++) for later use. The end result is extremely stable solutions that can run as fast as 5 microseconds on recent processors

MoveIt! IKFast

MoveIt! IKFast is a tool that generates a IKFast kinematics plugin for MoveIt using OpenRave generated cpp files. This tutorial will step you through setting up your robot to utilize the power of IKFast. MoveIt! IKFast is tested on ROS Groovy with Catkin using OpenRave 0.8 with a 6dof and 7dof robot arm manipulator. While it works in theory, currently the IKFast plugin generator tool does not work with >7 degree of freedom arms.

Pre-requisites

You should have already created a MoveIt! configuration package for your robot, by using the Setup Assistant.

MoveIt! IKFast Installation

Install the MoveIt! IKFast package either from debs or from source.

Binary Install

sudo apt-get install ros-indigo-moveit-kinematics

Source

Inside your catkin workspace

git clone https://github.com/ros-planning/moveit.git
cd moveit
git checkout indigo-devel

OpenRAVE Installation

Binary Install (only Indigo / Ubuntu 14.04)

sudo apt-get install ros-indigo-openrave

Note: you have to set export PYTHONPATH=$PYTHONPATH:`openrave-config –python-dir` (2016.9.1)

Source Install

Thanks to instructions from Stéphane Caron in https://scaron.info/teaching/troubleshooting-openrave-installation.html

git clone --branch latest_stable https://github.com/rdiankov/openrave.git
cd openrave && mkdir build && cd build
cmake ..
make -j4
sudo make install

Working commit numbers 5cfc7444... confirmed for Ubuntu 14.04 and 9c79ea26... confirmed for Ubuntu 16.04, according to Stéphane Caron.

Please report your results with this on the moveit-users mailing list.

Create Collada File For Use With OpenRave

First you will need robot description file that is in Collada or OpenRave robot format.

If your robot is not in this format we recommend you create a ROS URDF file, then convert it to a Collada .dae file using the following command:

rosrun collada_urdf urdf_to_collada <myrobot_name>.urdf <myrobot_name>.dae

where <myrobot_name> is the name of your robot.

Often floating point issues arrise in converting a URDF file to Collada file, so a script has been created to round all the numbers down to x decimal places in your .dae file. Its probably best if you skip this step initially and see if IKFast can generate a solution with your default values, but if the generator takes longer than, say, an hour, try the following:

rosrun moveit_kinematics round_collada_numbers.py <input_dae> <output_dae> <decimal places>

From experience we recommend 5 decimal places, but if the OpenRave ikfast generator takes to long to find a solution, lowering the number of decimal places should help. For example:

rosrun moveit_kinematics round_collada_numbers.py <myrobot_name>.dae <myrobot_name>.rounded.dae 5

To see the links in your newly generated Collada file

You may need to install package libsoqt4-dev to have the display working:

openrave-robot.py <myrobot_name>.dae --info links

This is useful if you have a 7-dof arm and you need to fill in a –freeindex parameter, discussed later.

To test your newly generated Collada file in OpenRave:

openrave <myrobot_name>.dae

Create IKFast Solution CPP File

Once you have a numerically rounded Collada file its time to generate the C++ .h header file that contains the analytical IK solution for your robot.

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.

Choose Planning Group

If your robot has more than one arm or “planning group” that you want to generate an IKFast solution for, choose one to generate first. The following instructions will assume you have chosen one <planning_group_name> that you will create a plugin for. Once you have verified that the plugin works, repeat the following instructions for any other planning groups you have. For example, you might have 2 planning groups:

<planning_group_name> = "left_arm"
<planning_group_name> = "right_arm"

Open Source Feedback

See something that needs improvement? Please open a pull request on this GitHub page