BenchmarkExecutor.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015, Rice University
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Rice University nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ryan Luna */
36 
37 #pragma once
38 
40 
42 
51 
52 #include <map>
53 #include <vector>
54 #include <string>
55 #include <boost/function.hpp>
56 
58 {
62 {
63 public:
65  typedef std::map<std::string, std::string> PlannerRunData;
67  typedef std::vector<PlannerRunData> PlannerBenchmarkData;
68 
70  typedef boost::function<void(const moveit_msgs::MotionPlanRequest& request, planning_scene::PlanningScenePtr)>
72 
74  typedef boost::function<void(const moveit_msgs::MotionPlanRequest& request, planning_scene::PlanningScenePtr)>
76 
79  typedef boost::function<void(const moveit_msgs::MotionPlanRequest& request, PlannerBenchmarkData& benchmark_data)>
81 
84  typedef boost::function<void(const moveit_msgs::MotionPlanRequest& request, PlannerBenchmarkData& benchmark_data)>
86 
88  typedef boost::function<void(moveit_msgs::MotionPlanRequest& request)> PreRunEventFunction;
89 
91  typedef boost::function<void(const moveit_msgs::MotionPlanRequest& request,
94 
95  BenchmarkExecutor(const std::string& robot_description_param = "robot_description");
96  virtual ~BenchmarkExecutor();
97 
98  // Initialize the benchmark executor by loading planning pipelines from the
99  // given set of classes
100  void initialize(const std::vector<std::string>& plugin_classes);
101 
102  void addPreRunEvent(const PreRunEventFunction& func);
103  void addPostRunEvent(const PostRunEventFunction& func);
108 
109  virtual void clear();
110 
111  virtual bool runBenchmarks(const BenchmarkOptions& opts);
112 
113 protected:
114  struct BenchmarkRequest
115  {
116  std::string name;
117  moveit_msgs::MotionPlanRequest request;
118  };
119 
120  struct StartState
121  {
122  moveit_msgs::RobotState state;
123  std::string name;
124  };
125 
126  struct PathConstraints
127  {
128  std::vector<moveit_msgs::Constraints> constraints;
129  std::string name;
130  };
131 
132  struct TrajectoryConstraints
133  {
134  moveit_msgs::TrajectoryConstraints constraints;
135  std::string name;
136  };
137 
138  virtual bool initializeBenchmarks(const BenchmarkOptions& opts, moveit_msgs::PlanningScene& scene_msg,
139  std::vector<BenchmarkRequest>& queries);
140 
142  virtual bool loadBenchmarkQueryData(const BenchmarkOptions& opts, moveit_msgs::PlanningScene& scene_msg,
143  std::vector<StartState>& start_states,
144  std::vector<PathConstraints>& path_constraints,
145  std::vector<PathConstraints>& goal_constraints,
146  std::vector<TrajectoryConstraints>& traj_constraints,
147  std::vector<BenchmarkRequest>& queries);
148 
150  bool solved, double total_time);
151 
155  const std::vector<planning_interface::MotionPlanDetailedResponse>& responses,
156  const std::vector<bool>& solved);
157 
163  const robot_trajectory::RobotTrajectory& traj_second, double& result_distance);
164 
165  virtual void writeOutput(const BenchmarkRequest& brequest, const std::string& start_time, double benchmark_duration);
166 
167  void shiftConstraintsByOffset(moveit_msgs::Constraints& constraints, const std::vector<double>& offset);
168 
170  bool plannerConfigurationsExist(const std::map<std::string, std::vector<std::string>>& planners,
171  const std::string& group_name);
172 
174  bool queriesAndPlannersCompatible(const std::vector<BenchmarkRequest>& requests,
175  const std::map<std::string, std::vector<std::string>>& planners);
176 
178  bool loadPlanningScene(const std::string& scene_name, moveit_msgs::PlanningScene& scene_msg);
179 
181  bool loadStates(const std::string& regex, std::vector<StartState>& start_states);
182 
184  bool loadPathConstraints(const std::string& regex, std::vector<PathConstraints>& constraints);
185 
187  bool loadTrajectoryConstraints(const std::string& regex, std::vector<TrajectoryConstraints>& constraints);
188 
190  bool loadQueries(const std::string& regex, const std::string& scene_name, std::vector<BenchmarkRequest>& queries);
191 
193  void createRequestCombinations(const BenchmarkRequest& brequest, const std::vector<StartState>& start_states,
194  const std::vector<PathConstraints>& path_constraints,
195  std::vector<BenchmarkRequest>& combos);
196 
198  void runBenchmark(moveit_msgs::MotionPlanRequest request,
199  const std::map<std::string, std::vector<std::string>>& planners, int runs);
200 
207 
209  planning_scene::PlanningScenePtr planning_scene_;
210 
212 
213  std::map<std::string, planning_pipeline::PlanningPipelinePtr> planning_pipelines_;
214 
215  std::vector<PlannerBenchmarkData> benchmark_data_;
216 
217  std::vector<PreRunEventFunction> pre_event_fns_;
218  std::vector<PostRunEventFunction> post_event_fns_;
219  std::vector<PlannerStartEventFunction> planner_start_fns_;
220  std::vector<PlannerCompletionEventFunction> planner_completion_fns_;
221  std::vector<QueryStartEventFunction> query_start_fns_;
222  std::vector<QueryCompletionEventFunction> query_end_fns_;
223 };
224 } // namespace moveit_ros_benchmarks
response
const std::string response
BenchmarkOptions.h
moveit_ros_benchmarks::BenchmarkExecutor::query_start_fns_
std::vector< QueryStartEventFunction > query_start_fns_
Definition: BenchmarkExecutor.h:285
moveit_ros_benchmarks::BenchmarkExecutor::planning_scene_
planning_scene::PlanningScenePtr planning_scene_
Definition: BenchmarkExecutor.h:273
moveit_ros_benchmarks::BenchmarkExecutor::runBenchmark
void runBenchmark(moveit_msgs::MotionPlanRequest request, const std::map< std::string, std::vector< std::string >> &planners, int runs)
Execute the given motion plan request on the set of planners for the set number of runs.
Definition: BenchmarkExecutor.cpp:758
moveit_ros_benchmarks::BenchmarkExecutor::planning_pipelines_
std::map< std::string, planning_pipeline::PlanningPipelinePtr > planning_pipelines_
Definition: BenchmarkExecutor.h:277
moveit_ros_benchmarks::BenchmarkExecutor::PlannerStartEventFunction
boost::function< void(const moveit_msgs::MotionPlanRequest &request, PlannerBenchmarkData &benchmark_data)> PlannerStartEventFunction
Definition: BenchmarkExecutor.h:144
moveit_ros_benchmarks::BenchmarkExecutor::queriesAndPlannersCompatible
bool queriesAndPlannersCompatible(const std::vector< BenchmarkRequest > &requests, const std::map< std::string, std::vector< std::string >> &planners)
Check that the given requests can be run on the set of planner plugins and algorithms.
Definition: BenchmarkExecutor.cpp:255
planning_scene_world_storage.h
moveit_warehouse::RobotStateStorage
planning_scene_storage.h
moveit_ros_benchmarks::BenchmarkExecutor::runBenchmarks
virtual bool runBenchmarks(const BenchmarkOptions &opts)
Definition: BenchmarkExecutor.cpp:204
moveit_ros_benchmarks::BenchmarkExecutor::plannerConfigurationsExist
bool plannerConfigurationsExist(const std::map< std::string, std::vector< std::string >> &planners, const std::string &group_name)
Check that the desired planner plugins and algorithms exist for the given group.
Definition: BenchmarkExecutor.cpp:509
moveit_ros_benchmarks::BenchmarkExecutor::tcs_
moveit_warehouse::TrajectoryConstraintsStorage * tcs_
Definition: BenchmarkExecutor.h:270
moveit_ros_benchmarks::BenchmarkExecutor::writeOutput
virtual void writeOutput(const BenchmarkRequest &brequest, const std::string &start_time, double benchmark_duration)
Definition: BenchmarkExecutor.cpp:1059
constraints_storage.h
moveit_warehouse::PlanningSceneWorldStorage
moveit_ros_benchmarks::BenchmarkExecutor::TrajectoryConstraints::name
std::string name
Definition: BenchmarkExecutor.h:199
state_storage.h
moveit_ros_benchmarks::BenchmarkExecutor::computeTrajectoryDistance
bool computeTrajectoryDistance(const robot_trajectory::RobotTrajectory &traj_first, const robot_trajectory::RobotTrajectory &traj_second, double &result_distance)
Definition: BenchmarkExecutor.cpp:989
moveit_warehouse::ConstraintsStorage
moveit_ros_benchmarks::BenchmarkExecutor::options_
BenchmarkOptions options_
Definition: BenchmarkExecutor.h:275
robot_trajectory::RobotTrajectory
planning_scene_monitor::PlanningSceneMonitor
moveit_warehouse::TrajectoryConstraintsStorage
moveit_ros_benchmarks::BenchmarkExecutor::loadQueries
bool loadQueries(const std::string &regex, const std::string &scene_name, std::vector< BenchmarkRequest > &queries)
Load all motion plan requests matching the given regular expression from the warehouse.
Definition: BenchmarkExecutor.cpp:604
database_loader.h
moveit_ros_benchmarks::BenchmarkExecutor::loadBenchmarkQueryData
virtual bool loadBenchmarkQueryData(const BenchmarkOptions &opts, moveit_msgs::PlanningScene &scene_msg, std::vector< StartState > &start_states, std::vector< PathConstraints > &path_constraints, std::vector< PathConstraints > &goal_constraints, std::vector< TrajectoryConstraints > &traj_constraints, std::vector< BenchmarkRequest > &queries)
Initialize benchmark query data from start states and constraints.
Definition: BenchmarkExecutor.cpp:401
moveit_ros_benchmarks::BenchmarkExecutor::PlannerRunData
std::map< std::string, std::string > PlannerRunData
Structure to hold information for a single run of a planner.
Definition: BenchmarkExecutor.h:129
moveit_ros_benchmarks::BenchmarkExecutor::PlannerBenchmarkData
std::vector< PlannerRunData > PlannerBenchmarkData
Structure to hold information for a single planner's benchmark data.
Definition: BenchmarkExecutor.h:131
moveit_ros_benchmarks::BenchmarkExecutor::addPostRunEvent
void addPostRunEvent(const PostRunEventFunction &func)
Definition: BenchmarkExecutor.cpp:179
moveit_ros_benchmarks::BenchmarkExecutor::loadPlanningScene
bool loadPlanningScene(const std::string &scene_name, moveit_msgs::PlanningScene &scene_msg)
Load the planning scene with the given name from the warehouse.
Definition: BenchmarkExecutor.cpp:568
planning_scene_monitor.h
moveit_ros_benchmarks::BenchmarkExecutor::benchmark_data_
std::vector< PlannerBenchmarkData > benchmark_data_
Definition: BenchmarkExecutor.h:279
moveit_ros_benchmarks::BenchmarkExecutor::planner_completion_fns_
std::vector< PlannerCompletionEventFunction > planner_completion_fns_
Definition: BenchmarkExecutor.h:284
moveit_ros_benchmarks::BenchmarkExecutor::collectMetrics
virtual void collectMetrics(PlannerRunData &metrics, const planning_interface::MotionPlanDetailedResponse &mp_res, bool solved, double total_time)
Definition: BenchmarkExecutor.cpp:846
moveit_ros_benchmarks::BenchmarkExecutor::initialize
void initialize(const std::vector< std::string > &plugin_classes)
Definition: BenchmarkExecutor.cpp:101
moveit_ros_benchmarks::BenchmarkExecutor::BenchmarkRequest
Definition: BenchmarkExecutor.h:178
moveit_ros_benchmarks::BenchmarkExecutor::addPlannerStartEvent
void addPlannerStartEvent(const PlannerStartEventFunction &func)
Definition: BenchmarkExecutor.cpp:184
moveit_ros_benchmarks::BenchmarkExecutor::clear
virtual void clear()
Definition: BenchmarkExecutor.cpp:137
moveit_ros_benchmarks::BenchmarkExecutor::TrajectoryConstraints::constraints
moveit_msgs::TrajectoryConstraints constraints
Definition: BenchmarkExecutor.h:198
moveit_warehouse::PlanningSceneStorage
moveit_ros_benchmarks::BenchmarkExecutor::StartState::state
moveit_msgs::RobotState state
Definition: BenchmarkExecutor.h:186
moveit_ros_benchmarks::BenchmarkExecutor::TrajectoryConstraints
Definition: BenchmarkExecutor.h:196
moveit_ros_benchmarks::BenchmarkExecutor::BenchmarkExecutor
BenchmarkExecutor(const std::string &robot_description_param="robot_description")
Definition: BenchmarkExecutor.cpp:80
class_loader.hpp
moveit_ros_benchmarks::BenchmarkExecutor::cs_
moveit_warehouse::ConstraintsStorage * cs_
Definition: BenchmarkExecutor.h:269
moveit_ros_benchmarks::BenchmarkExecutor::addQueryCompletionEvent
void addQueryCompletionEvent(const QueryCompletionEventFunction &func)
Definition: BenchmarkExecutor.cpp:199
trajectory_constraints_storage.h
moveit_ros_benchmarks::BenchmarkExecutor::initializeBenchmarks
virtual bool initializeBenchmarks(const BenchmarkOptions &opts, moveit_msgs::PlanningScene &scene_msg, std::vector< BenchmarkRequest > &queries)
Definition: BenchmarkExecutor.cpp:276
planning_pipeline.h
moveit_ros_benchmarks::BenchmarkExecutor::addPlannerCompletionEvent
void addPlannerCompletionEvent(const PlannerCompletionEventFunction &func)
Definition: BenchmarkExecutor.cpp:189
moveit_ros_benchmarks::BenchmarkExecutor::planner_start_fns_
std::vector< PlannerStartEventFunction > planner_start_fns_
Definition: BenchmarkExecutor.h:283
moveit_ros_benchmarks::BenchmarkExecutor::dbloader
warehouse_ros::DatabaseLoader dbloader
Definition: BenchmarkExecutor.h:272
moveit_ros_benchmarks::BenchmarkExecutor::addQueryStartEvent
void addQueryStartEvent(const QueryStartEventFunction &func)
Definition: BenchmarkExecutor.cpp:194
moveit_ros_benchmarks::BenchmarkExecutor::addPreRunEvent
void addPreRunEvent(const PreRunEventFunction &func)
Definition: BenchmarkExecutor.cpp:174
warehouse_ros::DatabaseLoader
moveit_ros_benchmarks::BenchmarkExecutor::createRequestCombinations
void createRequestCombinations(const BenchmarkRequest &brequest, const std::vector< StartState > &start_states, const std::vector< PathConstraints > &path_constraints, std::vector< BenchmarkRequest > &combos)
Duplicate the given benchmark request for all combinations of start states and path constraints.
Definition: BenchmarkExecutor.cpp:461
moveit_ros_benchmarks::BenchmarkExecutor::BenchmarkRequest::name
std::string name
Definition: BenchmarkExecutor.h:180
moveit_ros_benchmarks::BenchmarkExecutor::PostRunEventFunction
boost::function< void(const moveit_msgs::MotionPlanRequest &request, const planning_interface::MotionPlanDetailedResponse &response, PlannerRunData &run_data)> PostRunEventFunction
Definition of a post-run benchmark event function. Invoked immediately after each planner calls solve...
Definition: BenchmarkExecutor.h:157
moveit_ros_benchmarks::BenchmarkExecutor::PathConstraints::name
std::string name
Definition: BenchmarkExecutor.h:193
moveit_ros_benchmarks::BenchmarkExecutor::BenchmarkRequest::request
moveit_msgs::MotionPlanRequest request
Definition: BenchmarkExecutor.h:181
moveit_ros_benchmarks::BenchmarkExecutor::psws_
moveit_warehouse::PlanningSceneWorldStorage * psws_
Definition: BenchmarkExecutor.h:267
moveit_ros_benchmarks::BenchmarkExecutor::computeAveragePathSimilarities
void computeAveragePathSimilarities(PlannerBenchmarkData &planner_data, const std::vector< planning_interface::MotionPlanDetailedResponse > &responses, const std::vector< bool > &solved)
Definition: BenchmarkExecutor.cpp:944
moveit_ros_benchmarks::BenchmarkExecutor::shiftConstraintsByOffset
void shiftConstraintsByOffset(moveit_msgs::Constraints &constraints, const std::vector< double > &offset)
Definition: BenchmarkExecutor.cpp:439
moveit_ros_benchmarks::BenchmarkExecutor::loadTrajectoryConstraints
bool loadTrajectoryConstraints(const std::string &regex, std::vector< TrajectoryConstraints > &constraints)
Load all trajectory constraints from the warehouse that match the given regular expression.
Definition: BenchmarkExecutor.cpp:722
moveit_ros_benchmarks::BenchmarkOptions
Definition: BenchmarkOptions.h:79
moveit_ros_benchmarks::BenchmarkExecutor::pre_event_fns_
std::vector< PreRunEventFunction > pre_event_fns_
Definition: BenchmarkExecutor.h:281
moveit_ros_benchmarks::BenchmarkExecutor::query_end_fns_
std::vector< QueryCompletionEventFunction > query_end_fns_
Definition: BenchmarkExecutor.h:286
moveit_ros_benchmarks::BenchmarkExecutor::PlannerCompletionEventFunction
boost::function< void(const moveit_msgs::MotionPlanRequest &request, PlannerBenchmarkData &benchmark_data)> PlannerCompletionEventFunction
Definition: BenchmarkExecutor.h:149
moveit_ros_benchmarks::BenchmarkExecutor
Definition: BenchmarkExecutor.h:93
moveit_ros_benchmarks::BenchmarkExecutor::QueryCompletionEventFunction
boost::function< void(const moveit_msgs::MotionPlanRequest &request, planning_scene::PlanningScenePtr)> QueryCompletionEventFunction
Definition of a query-end benchmark event function. Invoked after a query has finished benchmarking.
Definition: BenchmarkExecutor.h:139
moveit_ros_benchmarks::BenchmarkExecutor::loadStates
bool loadStates(const std::string &regex, std::vector< StartState > &start_states)
Load all states matching the given regular expression from the warehouse.
Definition: BenchmarkExecutor.cpp:649
moveit_ros_benchmarks::BenchmarkExecutor::PathConstraints::constraints
std::vector< moveit_msgs::Constraints > constraints
Definition: BenchmarkExecutor.h:192
moveit_ros_benchmarks::BenchmarkExecutor::QueryStartEventFunction
boost::function< void(const moveit_msgs::MotionPlanRequest &request, planning_scene::PlanningScenePtr)> QueryStartEventFunction
Definition of a query-start benchmark event function. Invoked before a new query is benchmarked.
Definition: BenchmarkExecutor.h:135
moveit_ros_benchmarks::BenchmarkExecutor::pss_
moveit_warehouse::PlanningSceneStorage * pss_
Definition: BenchmarkExecutor.h:266
moveit_ros_benchmarks::BenchmarkExecutor::PreRunEventFunction
boost::function< void(moveit_msgs::MotionPlanRequest &request)> PreRunEventFunction
Definition of a pre-run benchmark event function. Invoked immediately before each planner calls solve...
Definition: BenchmarkExecutor.h:152
moveit_ros_benchmarks::BenchmarkExecutor::~BenchmarkExecutor
virtual ~BenchmarkExecutor()
Definition: BenchmarkExecutor.cpp:91
moveit_ros_benchmarks::BenchmarkExecutor::post_event_fns_
std::vector< PostRunEventFunction > post_event_fns_
Definition: BenchmarkExecutor.h:282
moveit_ros_benchmarks::BenchmarkExecutor::StartState::name
std::string name
Definition: BenchmarkExecutor.h:187
moveit_ros_benchmarks::BenchmarkExecutor::rs_
moveit_warehouse::RobotStateStorage * rs_
Definition: BenchmarkExecutor.h:268
planning_interface::MotionPlanDetailedResponse
moveit_ros_benchmarks
Definition: BenchmarkExecutor.h:57
moveit_ros_benchmarks::BenchmarkExecutor::loadPathConstraints
bool loadPathConstraints(const std::string &regex, std::vector< PathConstraints > &constraints)
Load all constraints matching the given regular expression from the warehouse.
Definition: BenchmarkExecutor.cpp:687
moveit_ros_benchmarks::BenchmarkExecutor::psm_
planning_scene_monitor::PlanningSceneMonitor * psm_
Definition: BenchmarkExecutor.h:265


benchmarks
Author(s): Ryan Luna
autogenerated on Sat May 3 2025 02:27:17