Contents
- 1 Overview
- 2 Generating Custom IKFast for Baxter
- 2.1 Install OpenRAVE
- 2.2 Clone the baxter_custom_ikfast Repository
- 2.3 Extracting the Mount Joint Transform
- 2.4 Modify Simplified URDFs with your robot's joints
- 2.5 Create DAEs for Each Arm
- 2.6 Rounding DAEs for Each Arm
- 2.7 Choose IK Type
- 2.8 Generate the IKFast Solver
- 2.9 Testing with the IKFastDemo
Overview
Every Baxter's URDF is slightly different. This tutorial will show you how to generate IKFast for use with MoveIt specific to your Baxter. This is a fairly involved process, requiring many steps. For additional background information on the algorithm behind IKFast, please see Rosen Diankov's Doctoral thesis. Another really good tutorial for generating IKFast for generic (non-Baxter) robots can be found on MoveIt's website: http://moveit.ros.org/wiki/Kinematics/IKFast
What is IKFast?
#ikfast IKFast provides analytical closed-form solutions for manipulator inverse kinematics. Part of the OpenRAVE robot architecture/software framework, IKFast has been used to provide closed-form solutions for Baxter's inverse kinematics. Advantages include order of magnitude faster IK solutions and the ability explore the manipulator's null space!
Using Baxter's MoveIt! IKFast plugins
Please see MoveIt_Tutorial#IKFast for the exact commands required to enable IKFast in your baxter_moveit_config package.
Generating Custom IKFast for Baxter
Install OpenRAVE
As of this writing, the instructions for adding the openrave PPA and installing openrave debians does not work on Ubuntu Trusty since the latest release was created in 2012 for Precise. That leaves building from source as the only option. Please clone the OpenRAVE repo and follow this tutorial for building from source:
git clone --branch latest_stable https://github.com/rdiankov/openrave.git
If you encounter any issues in building this repo, please let the developers know in the issues tab of their repo.
Clone the baxter_custom_ikfast Repository
To create IKFast for Baxter, we need to break him down into her individual arms. For this tutorial, we split Baxter into left and right arm URDFs and then removed any link/joint not in the kinematic chain between the base and end-effector. The result of this is a simple little repository on GitHub with these split URDFs in their generic form. Clone the baxter_custom_ikfast
repo anywhere, but make sure you are inside a initialized baxter.sh shell for commands later on.
$ git clone https://github.com/RethinkRobotics/baxter_custom_ikfast.git
Navigate inside this cloned folder for the rest of this tutorial:
$ cd custom_baxter_ikfast
Extracting the Mount Joint Transform
The left and right arm mount joint's in Baxter's torso are hand-welded at manufacture time. These joints are carefully measured and the transforms are stored in your Baxter's torso joint board. Fortunately, we can see the transforms in your robot's URDF located in the /robot_description parameter on the param server. After a fresh boot (to ensure the custom URDF has not been overwritten), from a properly initialized Baxter environment, export the URDF from the /robot_description
parameter on the ROS parameter server where it is stored, to a file of your choice (ex: baxter_urdf.xml
):
$ rosparam get -p /robot_description | tail -n +2 > baxter_urdf.xml
The -p
outputs the parameter using pretty print. The output urdf is piped through the tail
command first to remove a dummy first line - an artifact of the pretty print.
Open baxter_urdf.xml
in your favorite text editor, and search for torso_arm_mount
to which are the only joints that differ from Baxter to Baxter. This is an example of what you should expect if the robot description contains Baxter's custom joints:
<joint name="left_torso_arm_mount" type="fixed">
<origin xyz="0.0229088 0.220982 0.106714" rpy="-0.0179406 0.0117677 0.786034" />
<axis xyz="0 0 0" />
<parent link="torso" />
<child link="left_arm_mount" />
</joint>
and
<joint name="right_torso_arm_mount" type="fixed">
<origin xyz="0.0245182 -0.218624 0.10866" rpy="-0.00321838 -0.00564277 -0.78571" />
<axis xyz="0 0 0" />
<parent link="torso" />
<child link="right_arm_mount" />
</joint>
- Note: Save just the origin transform snippits of URDF for the next step. Be sure to avoid copying the parent link value torso as IKFast optimizes it out due to it being an identity transform and replaces it with base.
- Note: If you see the following joint values, then you are using the generic URDF provided in
baxter_description
of the SDK. This can happen if the generic URDF is loaded to the param server via aroslaunch
script (such as the one with MoveIt). Reboot your robot to clear therobot_description
and try again:
<joint name="left_torso_arm_mount" type="fixed">
<origin rpy="0 0 0.7854" xyz="0.024645 0.219645 0.118588"/>
<parent link="torso"/>
<child link="left_arm_mount"/>
</joint>
<joint name="right_torso_arm_mount" type="fixed">
<origin rpy="0 0 -0.7854" xyz="0.024645 -0.219645 0.118588"/>
<parent link="torso"/>
<child link="right_arm_mount"/>
</joint>
Modify Simplified URDFs with your robot's joints
The baxter_arm.accurate.<side>.urdf
was extracted from Baxter's original urdf to separate out the left and right arms. Inside the baxter_custom_ikfast
folder, edit both baxter_arm.accurate.<side>.urdf
's with your favorite text editor:
Replace the origin tag with your copied transform values inside the <side>_torso_arm_mount joints:
<joint name="left_torso_arm_mount" type="fixed">
<origin rpy="0 0 0.7854" xyz="0.024645 0.219645 0.118588"/>
<parent link="base"/>
<child link="left_arm_mount"/>
</joint>
Save, quit, and repeat for the other arm's urdf.
Create DAEs for Each Arm
Create our DAEs for each arm:
sudo apt-get install ros-indigo-robot-model
- Note: Please use the a simplified version of the urdf to only contain each manipulators links/joints modified with your robot's arm mount joint extracted above
rosrun collada_urdf urdf_to_collada baxter_arm.accurate.right.urdf baxter_arm.right.dae
- Note: The resulting DAE also needs some tuning - specifically the rotational portions of the description.
Specifically, we will need to round values logically (ie. 119.9999999999999 to 120.0) This will be addressed in the next step.
Please take note of the link indices using the following command:
$ openrave0.9-robot.py baxter_arm.right.dae --info links name index parents ----------------------------------------------- base 0 right_arm_mount 1 base right_upper_shoulder 2 right_arm_mount right_lower_shoulder 3 right_upper_shoulder right_upper_elbow 4 right_lower_shoulder right_lower_elbow 5 right_upper_elbow right_upper_forearm 6 right_lower_elbow right_lower_forearm 7 right_upper_forearm right_wrist 8 right_lower_forearm right_hand 9 right_wrist right_gripper 10 right_hand ----------------------------------------------- name index parents
Likewise with the joints:
$ openrave0.9-robot.py baxter_arm.right.dae --info joints name joint_index dof_index parent_link child_link mimic ------------------------------------------------------------------------------------------- right_s0 0 0 right_arm_mount right_upper_shoulder right_s1 1 1 right_upper_shoulder right_lower_shoulder right_e0 2 2 right_lower_shoulder right_upper_elbow right_e1 3 3 right_upper_elbow right_lower_elbow right_w0 4 4 right_lower_elbow right_upper_forearm right_w1 5 5 right_upper_forearm right_lower_forearm right_w2 6 6 right_lower_forearm right_wrist right_torso_arm_mount -1 -1 base right_arm_mount right_hand -1 -1 right_wrist right_hand right_endpoint -1 -1 right_hand right_gripper ------------------------------------------------------------------------------------------- name joint_index dof_index parent_link child_link mimic
Rounding DAEs for Each Arm
The openrave solver takes a lot longer to calculate solutions with many decimal points inside the numbers of the DAE files. To remedy this, download moveit_ikfast:
$ sudo apt-get install ros-indigo-moveit-ikfast
Let's round the numbers to five decimal points:
$ rosrun moveit_ikfast round_collada_numbers.py baxter_arm.right.dae baxter_arm.right.rounded.dae 5
Choose IK Type
Choose your IK Type (ex: Transform6D, Rotation3d, Translation3D, etc.)
http://openrave.org/docs/latest_stable/openravepy/ikfast/#ik-types
For most applications it makes sense to use transform6D - Baxter's end effector reaches desired 6D transformation
Generate the IKFast Solver
Building the solver using the collada mesh, chosen iktype, base, and end effector links created and found in the previous steps.
$ python /path_to_openrave/openrave/python/ikfast.py --robot=baxter_arm.right.rounded.dae --iktype=transform6d --baselink=1 --eelink=10 --freeindex=5 --savefile=baxter_right_arm_ikfast_solver.cpp
Completion time should be ~24 minutes.
This library is what exists inside the official moveit_robots/baxter_ikfast_<side>_arm_plugin package.
Simply drop this cpp file in there, rebuild your catkin workspace, and enable IKFast as explained in MoveIt_Tutorial#IKFast.
Congrats! You've created a custom IKFast for your Baxter!
Testing with the IKFastDemo
If you'd like to explore IKFast a bit further, you can compile the source code into an executable
$ g++ -lstdc++ -o baxter_right_ik baxter_right_arm_ikfast_solver.cpp -llapack
And finally, to go even further by testing out the ikfastdemo, first download it from the kaist-ros-pkg with wget:
$ wget http://kaist-ros-pkg.googlecode.com/svn/trunk/arm_kinematics_tools/src/ikfastdemo/ikfastdemo.cpp
Then edit the ikfastdemo.cpp
source file in your favorite text editor.
Modify the following lines at the top of the file:
#define IK_VERSION 61
#include "baxter_right_arm_ikfast_solver.cpp"
Then compile your IKFastDemo:
$ g++ ikfastdemo.cpp -lstdc++ -llapack -o compute -lrt