Skip to content

Conversion with urdf2graspit

Jennifer Buehler edited this page Apr 12, 2016 · 15 revisions

GraspIt! requires a special xml format to read the robot files. GraspIt maintains an internal representation of the robot with the Denavit-Hartenberg parameters, to which you need to convert your URDF model. You can use the package urdf2graspit to convert your URDF to Denavit-Hartenberg and the the GraspIt! format.

This tutorial is kept on a general level for all robots, illustrating with the example of the Jaco arm in jaco-arm-pkgs.

Preparation: Get your URDF file

You will need to use a .urdf file, not a .xacro file. To convert xacro to URDF you can use:

rosrun xacro xacro --inorder <your-xacro-file>.xacro > <your-urdf-output-file>.urdf

If you want to use the Jaco example:

roscd jaco_description
rosrun xacro xacro --inorder urdf/jaco_robot.urdf.xacro > urdf/jaco_robot.urdf

You may also be interested in the package urdf2inventor which provides a viewer which can help you find the right link names on your robot URDF.

Step 1: Start the converter

Run the conversion of your URDF file as follows:

rosrun urdf2graspit urdf2graspit_node \\
    `rospack find <YOUR_ROBOT>_description`/urdf/<YOUR_ROBOT>.urdf \
    <DESTINATION_FOLDER> <WRIST_LINK_NAME> <FINGER_JOINT_NAME1> <FINGER_JOINT_NAME2> ...

The finger joint names have to be the root joints of the movable gippers, and the wrist link needs to be a link to which all these joints are attached (there may be fixed joints in-between the wrist link and the finger joints, but no active joints!).

For the Jaco example, there is a launch file to run the conversion on the Jaco robot. You may inspect this launch file and adapt it for your robot.

roslaunch urdf2graspit example_urdf2graspit_jaco.launch output_directory:=<your-output-directory>

This will convert the robot and save the files in the specified output directory.

Step 2 [optional]: Choose your contact points in the viewer

The last step has converted the robot files including the meshes, but it has not created contact points yet. This requires an interactive selection by the user. You may skip this step, but it is recommended to generate contacts, because the grasp planner works a lot better with it.

Start the interactive viewer:

rosrun urdf2graspit contacts_generator_node \
    `rospack find <YOUR_ROBOT>_description`/urdf/<YOUR_ROBOT>.urdf \
    <DESTINATION_FOLDER> <WRIST_LINK_NAME> <FINGER_JOINT_NAME1> <FINGER_JOINT_NAME2> ...

For the Jaco example, there is a launch file which you may use as a template for your own robot:

roslaunch urdf2graspit example_graspit_contacts_jaco.launch output_directory:=<your-output-directory>

Tipp: to change the filename of the generated contacts file (e.g. if you would like to generate several contact files), add the argument "filename". The specified file will be saved into <output_directory>/models/robots/<your_robot_name>/virtual.

roslaunch urdf2graspit example_graspit_contacts_jaco.launch \
    output_directory:=<your-output-directory> filename:=<filename>.vgr

The viewer will open in which you can see your converted hand model. Click on the mouse pointer (small arrow) on the right-hand pane to enable the contact point selection.

You can now select the contact points on the hand by clicking once on the hand surface where you want points to be added.

If you want to move the hand again, you have to click on the hand symbol again to enable the scene rotation mode. You may also want to click on the eye symbol (right-hand pane) first, to switch into object-centered camera mode.

Make sure you select good contact points on the fingers. You do not necessarily need many, usually around 3-6 contacts per finger yield good results, depending on the hand. There should be a few on each finger and some on the palm as well.

When you are finshed, close the window (clicking on the "x"), and the GraspIt! files will be generated.

Notes:

  • The mesh of the Jaco does not perfectly fit at the base of the fingers. This is because adaptations had to be made to the model in order to more closely reflect the real robot. This should be updated some time.
  • If you did not have roscore running in another terminal, you may have to quit with [Ctrl+C]. The converter node has finished cleanly after the message "Cleaning up... Done." has been printed.

Step 3: Inspect the results

The folder DESTINATION_FOLDER will contain the following files and folders:

  • models/robots/YOUR_ROBOT
    • eigen: contains eigen.xml
    • iv: contains all inventor geometry folders
    • YOUR_ROBOT.xml
    • virtual: contains contacts.vgr
  • worlds:
    • YOUR_ROBOT_world.xml

For example, on the Jaco robot the directory structure (print it with the tree command) looks as follows:

Before you can load your robot into the GraspIt! simulator GUI for inspection, you will also need to link the YOUR_ROBOT folder in the $GRASPIT/models/robots folder:

cd $GRASPIT/models/robots
ls -s <path-to-YOUR_ROBOT-folder>

And also link the generated world file:

cd $GRASPIT/worlds
ls -s <path-to-worlds>/YOUR_ROBOT_world.xml

For example, for the Jaco robot the commands expand to:

cd $GRASPIT/models/robots
ln -s <your-output-directory>/models/robots/jaco_robot/
cd $GRASPIT/worlds
ln -s <your-output-directory>/worlds/jaco_robot_world.xml

The default world file which is created by urdf2graspit has a section which is commented out which loads a cube object along with the robot. If you want to load an object, you may uncomment it in the world XML file and replace the filename with the object you with to load.

<?xml version="1.0"?>
<world>
    <!--
    <graspableBody>
        <filename>models/objects/cube.xml</filename>
        <transform>
        <fullTransform>(+1 0 0 0)[+100 +0 +0]</fullTransform>
        </transform>
    </graspableBody>
    -->
    <robot>
        <filename>models/robots/jaco_robot/jaco_robot.xml</filename>
        <dofValues>0.0045 0.0045 0.0045 </dofValues>
        <transform>
            <fullTransform>(+1 0 0 0)[0 0 0]</fullTransform>
        </transform>
    </robot>
    <camera>
        <position>+0 +0 +500</position>
        <orientation>0 0 0 1</orientation>
        <focalDistance>+500</focalDistance>
    </camera>
</world>

To inspect the hand, you can open your world file (YOUR_ROBOT_world.xml) from the GraspIt simulator. You can start the simulator with

rosrun graspit graspit_simulator

Or if you have compiled the simulator with the grasp_planning_graspit package:

rosrun grasp_planning_graspit graspit_simulator_standalone

The contact points are displayed as red lines.

You can now perform grasp planning for your hand using the simulator. Please refer to the simulator tutorial for this.

Note: The contact points generated by urdf2graspit may still need to be improved, I have not had the time to inspect how they can be defined better. So the grasp planning results may not be optimal. See also notes about the contact points below.

Info: The order of the joints in the GraspIt XML robot file are according to a depth-first search in the URDF tree.