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 #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
00073 moveit_msgs::PlanningScene scene;
00074
00075
00076 moveit_msgs::MotionPlanRequest motion_plan_request;
00077
00078
00079 std::vector<PlanningPluginOptions> plugins;
00080
00081 BenchmarkType benchmark_type;
00082
00083
00084 std::string filename;
00085
00086
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
00132 bool is_sweep;
00133 double start;
00134 double step_size;
00135 double end;
00136
00137
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