Go to the documentation of this file.00001 #ifdef DOXYGEN_SHOULD_SKIP_THIS
00002
00021 #endif // DOXYGEN_SHOULD_SKIP_THIS
00022
00023 #include <grasp_planning_graspit/GraspItSceneManagerHeadless.h>
00024 #include <grasp_planning_graspit/EigenGraspPlanner.h>
00025 #include <grasp_planning_graspit/EigenGraspResult.h>
00026 #include <string>
00027 #include <vector>
00028
00032 int main(int argc, char **argv)
00033 {
00034 if (argc < 3)
00035 {
00036 std::cerr << "Usage: " << argv[0] << " <world-filename> <output-directory>" << std::endl;
00037 return 1;
00038 }
00039
00040 std::string worldFilename = argv[1];
00041 std::string outputDirectory = argv[2];
00042
00043 if (worldFilename.empty())
00044 {
00045 std::cerr << "You have to specify a world" << std::endl;
00046 return 1;
00047 }
00048
00049
00050
00051 SHARED_PTR<GraspIt::GraspItSceneManager> graspitMgr(new GraspIt::GraspItSceneManagerHeadless());
00052
00053
00054 graspitMgr->loadWorld(worldFilename);
00055
00056
00057 bool createDir = true;
00058
00059
00060 graspitMgr->saveGraspItWorld(outputDirectory + "/worlds/startWorld.xml", createDir);
00061 graspitMgr->saveInventorWorld(outputDirectory + "/worlds/startWorld.iv", createDir);
00062
00063
00064 std::string name = "EigenGraspPlanner1";
00065 SHARED_PTR<GraspIt::EigenGraspPlanner> planner(new GraspIt::EigenGraspPlanner(name, graspitMgr));
00066
00067
00068 int maxPlanningSteps = 70000;
00069
00070 int repeatPlanning = 1;
00071
00072
00073 int keepMaxPlanningResults = 3;
00074
00075
00076
00077 bool finishWithAutograsp = false;
00078
00079
00080
00081
00082 if (!planner->plan(maxPlanningSteps, repeatPlanning, keepMaxPlanningResults, finishWithAutograsp))
00083 {
00084 std::cerr << "Error doing the planning." << std::endl;
00085 return 1;
00086 }
00087
00088
00089
00090
00091 std::string resultsWorldDirectory = outputDirectory + "/worlds";
00092
00093 std::string filenamePrefix = "world";
00094
00095 bool saveInventor = true;
00096
00097 bool saveGraspit = true;
00098
00099
00100
00101 planner->saveResultsAsWorldFiles(resultsWorldDirectory, filenamePrefix, saveGraspit, saveInventor, createDir);
00102
00103
00104
00105 std::vector<GraspIt::EigenGraspResult> allGrasps;
00106 planner->getResults(allGrasps);
00107
00108 std::cout << "Grasp results:" << std::endl;
00109 std::vector<GraspIt::EigenGraspResult>::iterator it;
00110 for (it = allGrasps.begin(); it != allGrasps.end(); ++it)
00111 {
00112 std::cout << *it << std::endl;;
00113 }
00114
00115 return 0;
00116 }