Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 #include <moveit/benchmarks/benchmark_execution.h>
00038 #include <moveit/planning_scene_monitor/planning_scene_monitor.h>
00039 #include <boost/program_options.hpp>
00040 #include <ros/ros.h>
00041 
00042 static const std::string ROBOT_DESCRIPTION =
00043     "robot_description";  
00044 
00045 int main(int argc, char** argv)
00046 {
00047   ros::init(argc, argv, "moveit_benchmarks", ros::init_options::AnonymousName);
00048 
00049   ros::AsyncSpinner spinner(1);
00050   spinner.start();
00051 
00052   boost::program_options::options_description desc;
00053   desc.add_options()("help", "Show help message")("host", boost::program_options::value<std::string>(), "Host for the "
00054                                                                                                         "DB.")(
00055       "port", boost::program_options::value<std::size_t>(), "Port for the DB.")(
00056       "benchmark-goal-existance", "Benchmark the sampling of the goal region")("benchmark-planners", "Benchmark only "
00057                                                                                                      "the planners");
00058 
00059   boost::program_options::variables_map vm;
00060   boost::program_options::parsed_options po = boost::program_options::parse_command_line(argc, argv, desc);
00061   boost::program_options::store(po, vm);
00062   boost::program_options::notify(vm);
00063 
00064   if (vm.count("help") || argc == 1)  
00065   {
00066     std::cout << desc << std::endl;
00067     return 1;
00068   }
00069   
00070   warehouse_ros::DatabaseConnection::Ptr conn = moveit_warehouse::loadDatabase();
00071   if (vm.count("host") && vm.count("port"))
00072     conn->setParams(vm["host"].as<std::string>(), vm["port"].as<std::size_t>());
00073   if (!conn->connect())
00074     return 1;
00075 
00076   planning_scene_monitor::PlanningSceneMonitor psm(ROBOT_DESCRIPTION);
00077   moveit_benchmarks::BenchmarkType btype = 0;
00078   moveit_benchmarks::BenchmarkExecution be(psm.getPlanningScene(), conn);
00079   if (vm.count("benchmark-planners"))
00080     btype += moveit_benchmarks::BENCHMARK_PLANNERS;
00081   if (vm.count("benchmark-goal-existance"))
00082     btype += moveit_benchmarks::BENCHMARK_GOAL_EXISTANCE;
00083 
00084   unsigned int proc = 0;
00085   std::vector<std::string> files =
00086       boost::program_options::collect_unrecognized(po.options, boost::program_options::include_positional);
00087   for (std::size_t i = 0; i < files.size(); ++i)
00088   {
00089     if (be.readOptions(files[i].c_str()))
00090     {
00091       std::stringstream ss;
00092       be.printOptions(ss);
00093       std::cout << "Calling benchmark with options:" << std::endl << ss.str() << std::endl;
00094       be.runAllBenchmarks(btype);
00095       proc++;
00096     }
00097   }
00098   ROS_INFO_STREAM("Processed " << proc << " benchmark configuration files");
00099 
00100   ROS_INFO("Benchmarks complete! Shutting down ROS...");  
00101   ros::shutdown();
00102 
00103   return 0;
00104 }