-
Notifications
You must be signed in to change notification settings - Fork 26
GraspIt CPP API Tutorial
This tutorial will discuss a simple example of how to use the GraspIt::GraspItSceneManager class and the GraspIt::EigenGraspPlanner class to:
- Load a graspit world
- Use the Eigengrasp planner on the loaded world
You may use the example files for the Kinova jaco robot provided in jaco_graspit_sample in this tutorial.
Install the packages as described in the installation instructions, either:
If you are using catkin, create a new package:
cd <catkin_ws>/src
catkin_create_pkg graspit_planning_tutorial grasp_planning_graspit
cd graspit_planning_tutorial
mkdir src
Otherwise, if you are compiling with cmake, just make a directory for this tutorial:
mkdir graspit_planning_tutorial
cd graspit_planning_tutorial
mkdir src
Create and open a C++ file which you will use for this example. Lets call it simple_planning_tutorial.cpp.
<your-editor> src/simple_planning_tutorial.cpp
First, you will need to include the relevant files. We will use the implementation of GraspItSceneManager which does not require running a GUI:
#include <grasp_planning_graspit/GraspItSceneManagerHeadless.h>
#include <grasp_planning_graspit/EigenGraspPlanner.h>
#include <grasp_planning_graspit/EigenGraspResult.h>
Now, we will create the GraspItSceneManager object, which should be maintained with a shared pointer:
// Create the graspit world manager.
SHARED_PTR<GraspIt::GraspItSceneManager> graspitMgr(new GraspIt::GraspItSceneManagerHeadless());
Now, load the world from a GraspIt xml file:
// The world file name will be the first argument
std::string worldFilename(argv[0]);
// Load the graspit world
graspitMgr->loadWorld(worldFilename);
Now the GraspIt world is initialized and the world is loaded.
You could now save the world again into another file, to verify that the loading process has been successful. This is particularly useful if you add several robots and objects (instead of only one world):
// if the output directory does not exist yet, create it?
bool createDir = true;
// the output directory will be the second argument
std::string outputDirectory(argv[1]);
// in case one wants to view the initial world before planning, save it.
graspitMgr->saveGraspItWorld(outputDirectory + "/worlds/startWorld.xml", createDir);
graspitMgr->saveInventorWorld(outputDirectory + "/worlds/startWorld.iv", createDir);
Now, we can create the EigenGraspPlanner instance and initialize it with the current GraspIt world. It is important also for the EigenGraspPlanner (or in general, for all GraspItAccessor subclasses) to maintain a shared pointer of it:
// Create the planner which accesses the graspit world.
SHARED_PTR<GraspIt::EigenGraspPlanner> planner(new GraspIt::EigenGraspPlanner("ChooseAnyPlannerName", graspitMgr));
Now, we can run the planning algorithm on the current world:
// By default, the last robot loaded and the last object loaded are to be used as the hand and the
// object to grasp for the planning process. You can use the other EigenGraspPlanner::plan()
// method with more parameters to change this.
// Number of iterations for the planning algorithm
int maxPlanningSteps = 70000;
// Number of times to repeat the planning process
int repeatPlanning = 1;
// Maximum number of planning results to keep (of each planning repeat)
int keepMaxPlanningResults = 3;
// Finalize each planning result with an "auto-grasp" to ensure there really are
// contacts between fingers and objects (sometimes, the grasp result is just very
// close to the object, but not really touching it).
bool finishWithAutograsp = false;
// By default, the last robot loaded and the last object loaded are to be used as the hand and the
// object to grasp for the planning process. You can use the other EigenGraspPlanner::plan()
// method with more parameters to change this.
if (!planner->plan(maxPlanningSteps, repeatPlanning, keepMaxPlanningResults, finishWithAutograsp))
{
std::cerr << "Error doing the planning." << std::endl;
...
}
If the planning was successful, you can now access the results either by:
- Option 1: Saving them as world files, and / or
- Option 2: Getting the resulting grasps as Result::EigenGraspResult objects.
Option 1: Saving the world files
We can save the resulting world files, in which the robot is just doing the grasp in a directory of your choice:
// specify where you want to save the worlds:
std::string resultsWorldDirectory = ...
// each result file will start with this prefix:
std::string filenamePrefix = "world";
// specify to save as inventor files:
bool saveInventor = true;
// specify to save as graspit world files:
bool saveGraspit = true;
// Now, save the results.
planner->saveResultsAsWorldFiles(resultsWorldDirectory, filenamePrefix, saveGraspit, saveInventor, createDir);
Option 2: Processing the grasp results.
You can do anything you like with the results. Have a look at class GraspIt::EigenGraspResult. For example, print the resulting grasp details:
// get the planning results
std::vector<GraspIt::EigenGraspResult> allGrasps;
planner->getResults(allGrasps);
// Iterate through all results and print information about the grasps:
std::cout << "Grasp results:" << std::endl;
std::vector<GraspIt::EigenGraspResult>::iterator it;
for (it = allGrasps.begin(); it != allGrasps.end(); ++it)
{
std::cout << *it << std::endl;;
}
If you are using catkin:
First, edit the CMakeLists.txt file which was generated for the catkin package and add the following lines at the right places (the template should have examples with equivalent commented commands)
add_executable(simple_planning_tutorial
src/simple_planning_tutorial.cpp)
...
target_link_libraries(simple_planning_tutorial
${catkin_LIBRARIES})
Now, you may compile as usual:
catkin_make
If you are using cmake only:
You may use the CMakeLists.txt file given in the tutorial directory.
cp <grasp_planning_graspit>/tutorial/CMakeLists.txt .
Make sure to adapt the add_executable
path to your .cpp file in the
CMakeLists.txt.
Now, you may build the tutorial code:
mkdir build
cd build
cmake -DCMAKE_PREFIX_PATH=<graspit-install-location>;<grasp_planning_graspit-install-location> ..
make
make install
Run the planning on a world file and specify the output directory for the results:
./simple_planning_tutorial <world-filename> <output-directory>
Note: If you are using catkin, prepend rosrun graspit_planning_tutorial
to the command.
For example, use the Jaco hand:
./simple_planning_tutorial `rospack find jaco_graspit_sample`/worlds/jaco_robot_world.xml <output-directory>
Don't forget to set your GRASPIt environment variable to jaco_graspit_sample
first, e.g. when using ROS:
export GRASPIT=`rospack find jaco_graspit_sample`
You can get the complete source code in grasp_planning_graspit/tutorial/src/simple_planning_tutorial.cpp
You may now want to try out your own robot, but you don't have the GraspIt files for it? Follow the urdf2graspit tutorial to see how you can convert a robot from URDF to GraspIt.