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


benchmarks
Author(s): Ioan Sucan
autogenerated on Wed Aug 26 2015 12:43:51