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 the 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="robot_description";      // name of the robot description (a param name, so it can be changed externally)
00043 
00044 int main(int argc, char **argv)
00045 {
00046   ros::init(argc, argv, "moveit_benchmarks", ros::init_options::AnonymousName);
00047 
00048   ros::AsyncSpinner spinner(1);
00049   spinner.start();
00050 
00051   boost::program_options::options_description desc;
00052   desc.add_options()
00053     ("help", "Show help message")
00054     ("host", boost::program_options::value<std::string>(), "Host for the MongoDB.")
00055     ("port", boost::program_options::value<std::size_t>(), "Port for the MongoDB.")
00056     ("benchmark-goal-existance", "Benchmark the sampling of the goal region")
00057     ("benchmark-planners", "Benchmark only 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 
00070   try
00071   {
00072     planning_scene_monitor::PlanningSceneMonitor psm(ROBOT_DESCRIPTION);
00073     moveit_benchmarks::BenchmarkType btype = 0;
00074     moveit_benchmarks::BenchmarkExecution be(psm.getPlanningScene(),
00075                                              vm.count("host") ? vm["host"].as<std::string>() : "",
00076                                              vm.count("port") ? vm["port"].as<std::size_t>() : 0);
00077     if (vm.count("benchmark-planners"))
00078       btype += moveit_benchmarks::BENCHMARK_PLANNERS;
00079     if (vm.count("benchmark-goal-existance"))
00080       btype += moveit_benchmarks::BENCHMARK_GOAL_EXISTANCE;
00081 
00082     unsigned int proc = 0;
00083     std::vector<std::string> files = boost::program_options::collect_unrecognized(po.options, boost::program_options::include_positional);
00084     for (std::size_t i = 0 ; i < files.size() ; ++i)
00085     {
00086       if (be.readOptions(files[i].c_str()))
00087       {
00088         std::stringstream ss;
00089         be.printOptions(ss);
00090         std::cout << "Calling benchmark with options:" << std::endl << ss.str() << std::endl;
00091         be.runAllBenchmarks(btype);
00092         proc++;
00093       }
00094     }
00095     ROS_INFO_STREAM("Processed " << proc << " benchmark configuration files");
00096   }
00097   catch(mongo_ros::DbConnectException &ex)
00098   {
00099     ROS_ERROR_STREAM("Unable to connect to warehouse. If you just created the database, it could take a while for initial setup. Please try to run the benchmark again."
00100                      << std::endl << ex.what());
00101   }
00102 
00103   ROS_INFO("Benchmarks complete! Shutting down ROS..."); // because sometimes there are segfaults after this
00104   ros::shutdown();
00105 
00106   return 0;
00107 }


benchmarks
Author(s): Ioan Sucan
autogenerated on Mon Oct 6 2014 02:32:28