benchmark_execution.h
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 #ifndef MOVEIT_BENCHMARKS_BENCHMARK_EXECUTION_
00038 #define MOVEIT_BENCHMARKS_BENCHMARK_EXECUTION_
00039 
00040 #include <moveit/warehouse/planning_scene_storage.h>
00041 #include <moveit/warehouse/planning_scene_world_storage.h>
00042 #include <moveit/warehouse/constraints_storage.h>
00043 #include <moveit/warehouse/trajectory_constraints_storage.h>
00044 #include <moveit/warehouse/state_storage.h>
00045 #include <moveit/planning_interface/planning_interface.h>
00046 #include <pluginlib/class_loader.h>
00047 #include <boost/function.hpp>
00048 #include <iostream>
00049 
00050 namespace moveit_benchmarks
00051 {
00052 typedef unsigned int BenchmarkType;
00053 static const BenchmarkType BENCHMARK_PLANNERS = 1;
00054 static const BenchmarkType BENCHMARK_GOAL_EXISTANCE = 2;
00055 
00056 typedef std::map<std::string, std::string> RunData;
00057 typedef std::vector<RunData> AlgorithmRunsData;
00058 
00059 struct PlanningPluginOptions
00060 {
00061   std::string name;
00062   std::vector<std::string> planners;
00063   std::size_t runs;
00064 };
00065 
00066 struct BenchmarkRequest
00067 {
00068   BenchmarkRequest() : benchmark_type(0)
00069   {
00070   }
00071 
00072   // The scene to consider in the benchmark
00073   moveit_msgs::PlanningScene scene;
00074 
00075   // The problem to benchmarked
00076   moveit_msgs::MotionPlanRequest motion_plan_request;
00077 
00078   // The planning plugins to use in the benchmark
00079   std::vector<PlanningPluginOptions> plugins;
00080 
00081   BenchmarkType benchmark_type;
00082 
00083   // The file where to store the results
00084   std::string filename;
00085 
00086   // Optional: name of goal - only used for later analysis
00087   std::string goal_name;
00088 };
00089 
00090 class BenchmarkExecution
00091 {
00092 public:
00093   BenchmarkExecution(const planning_scene::PlanningScenePtr& scene, warehouse_ros::DatabaseConnection::Ptr conn);
00094 
00095   bool readOptions(const std::string& filename);
00096   void printOptions(std::ostream& out);
00097 
00098   void runAllBenchmarks(BenchmarkType type);
00099 
00100   void runBenchmark(BenchmarkRequest& req);
00101   void runPlanningBenchmark(BenchmarkRequest& req);
00102   void runGoalExistenceBenchmark(BenchmarkRequest& req);
00103 
00104 private:
00105   struct BenchmarkOptions
00106   {
00107     std::string scene;
00108     std::string output;
00109     std::string start_regex;
00110     std::string query_regex;
00111     std::string goal_regex;
00112     std::string trajectory_regex;
00113     std::string group_override;
00114     std::string planning_frame;
00115     std::string default_constrained_link;
00116     std::size_t default_run_count;
00117     double offsets[6];
00118     double timeout;
00119 
00120     std::vector<PlanningPluginOptions> plugins;
00121 
00122     moveit_msgs::WorkspaceParameters workspace_parameters;
00123   };
00124 
00126   struct ParameterOptions
00127   {
00128     std::string key;
00129     std::string log_key;
00130 
00131     // Parameters for sweeping
00132     bool is_sweep;
00133     double start;
00134     double step_size;
00135     double end;
00136 
00137     // Parameters for fractional factorial analysis (design of experience)
00138     double high;
00139     double low;
00140   };
00141 
00143   typedef std::map<std::string, double> ParameterInstance;
00144 
00145   void collectMetrics(std::map<std::string, std::string>& rundata,
00146                       const planning_interface::MotionPlanDetailedResponse& mp_res, bool solved, double total_time);
00147 
00155   void modifyPlannerConfiguration(planning_interface::PlannerManager& planner, const std::string& planner_id,
00156                                   std::size_t param_combinations_id_, RunData& parameter_data);
00157 
00162   std::size_t generateParamCombinations();
00163 
00170   void recursiveParamCombinations(int options_id, ParameterInstance param_instance);
00171 
00173   void printConfigurationSettings(const planning_interface::PlannerConfigurationMap& settings, std::ostream& out);
00174 
00175   BenchmarkOptions options_;
00176   std::vector<ParameterOptions> param_options_;
00177   std::vector<ParameterInstance> param_combinations_;
00178 
00179   std::vector<std::string> available_plugins_;
00180   planning_scene::PlanningScenePtr planning_scene_;
00181 
00182   moveit_warehouse::PlanningSceneStorage pss_;
00183   moveit_warehouse::PlanningSceneWorldStorage psws_;
00184   moveit_warehouse::ConstraintsStorage cs_;
00185   moveit_warehouse::TrajectoryConstraintsStorage tcs_;
00186   moveit_warehouse::RobotStateStorage rs_;
00187 
00188   boost::shared_ptr<pluginlib::ClassLoader<planning_interface::PlannerManager> > planner_plugin_loader_;
00189   std::map<std::string, planning_interface::PlannerManagerPtr> planner_interfaces_;
00190 };
00191 }
00192 
00193 #endif


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