run_benchmarks.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Ioan Sucan */
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";  // name of the robot description (a param name, so it can be changed externally)
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)  // show help if no parameters passed
00065   {
00066     std::cout << desc << std::endl;
00067     return 1;
00068   }
00069   // Set up db
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...");  // because sometimes there are segfaults after this
00101   ros::shutdown();
00102 
00103   return 0;
00104 }


benchmarks
Author(s): Ioan Sucan
autogenerated on Mon Jul 24 2017 02:22:03