moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
BenchmarkExecutor.cpp
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
42#include <moveit/version.h>
43#include <tf2_eigen/tf2_eigen.hpp>
45
46#include <boost/regex.hpp>
47
48#if __has_include(<boost/timer/progress_display.hpp>)
49#include <boost/timer/progress_display.hpp>
50using boost_progress_display = boost::timer::progress_display;
51#else
52// boost < 1.72
53#define BOOST_TIMER_ENABLE_DEPRECATED 1
54#include <boost/progress.hpp>
55#undef BOOST_TIMER_ENABLE_DEPRECATED
56using boost_progress_display = boost::progress_display;
57#endif
58
59#include <boost/math/constants/constants.hpp>
60#include <boost/filesystem.hpp>
61#include <boost/date_time/posix_time/posix_time.hpp>
62#include <math.h>
63#include <limits>
64#include <filesystem>
65#ifndef _WIN32
66#include <unistd.h>
67#else
68#include <winsock2.h>
69#endif
70
71#undef max
72
73using namespace moveit_ros_benchmarks;
74
75namespace
76{
77rclcpp::Logger getLogger()
78{
79 return moveit::getLogger("moveit.benchmarks.executor");
80}
81} // namespace
82
83template <class Clock, class Duration>
84boost::posix_time::ptime toBoost(const std::chrono::time_point<Clock, Duration>& from)
85{
86 typedef std::chrono::nanoseconds duration_t;
87 typedef long rep_t;
88 rep_t d = std::chrono::duration_cast<duration_t>(from.time_since_epoch()).count();
89 rep_t sec = d / 1000000000;
90 rep_t nsec = d % 1000000000;
91 namespace pt = boost::posix_time;
92#ifdef BOOST_DATE_TIME_HAS_NANOSECONDS
93 return pt::from_time_t(sec) + pt::nanoseconds(nsec)
94#else
95 return pt::from_time_t(sec) + pt::microseconds(nsec / 1000);
96#endif
97}
98
99BenchmarkExecutor::BenchmarkExecutor(const rclcpp::Node::SharedPtr& node, const std::string& robot_descriptionparam)
100 : planning_scene_monitor_{ std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(node,
101 robot_descriptionparam) }
102 , planning_scene_storage_{ nullptr }
103 , planning_scene_world_storage_{ nullptr }
104 , robot_state_storage_{ nullptr }
105 , constraints_storage_{ nullptr }
106 , trajectory_constraints_storage_{ nullptr }
107 , node_{ node }
108 , db_loader_{ node }
109{
110 planning_scene_ = planning_scene_monitor_->getPlanningScene();
111}
112
116
117[[nodiscard]] bool BenchmarkExecutor::initialize(const std::vector<std::string>& planning_pipeline_names)
118{
119 // Initialize moveit_cpp
120 moveit_cpp_ = std::make_shared<moveit_cpp::MoveItCpp>(node_);
121
122 for (const std::string& planning_pipeline_name : planning_pipeline_names)
123 {
124 if (moveit_cpp_->getPlanningPipelines().find(planning_pipeline_name) == moveit_cpp_->getPlanningPipelines().end())
125 {
126 RCLCPP_ERROR(getLogger(), "Cannot find pipeline '%s'", planning_pipeline_name.c_str());
127 return false;
128 }
129
130 const auto& pipeline = moveit_cpp_->getPlanningPipelines().at(planning_pipeline_name);
131 // Verify the pipeline has successfully initialized a planner
132 if (!pipeline)
133 {
134 RCLCPP_ERROR(getLogger(), "Failed to initialize planning pipeline '%s'", planning_pipeline_name.c_str());
135 continue;
136 }
137 }
138
139 // Error check
140 if (moveit_cpp_->getPlanningPipelines().empty())
141 {
142 RCLCPP_ERROR(getLogger(), "No planning pipelines have been loaded. Nothing to do for the benchmarking service.");
143 }
144 else
145 {
146 RCLCPP_INFO(getLogger(), "Available planning pipelines:");
147 for (const std::pair<const std::string, planning_pipeline::PlanningPipelinePtr>& entry :
148 moveit_cpp_->getPlanningPipelines())
149 {
150 RCLCPP_INFO_STREAM(getLogger(), entry.first);
151 }
152 }
153 return true;
154}
155
157{
159 {
161 }
163 {
165 }
167 {
168 robot_state_storage_.reset();
169 }
171 {
172 constraints_storage_.reset();
173 }
175 {
177 }
178
179 benchmark_data_.clear();
180 pre_event_functions_.clear();
181 post_event_functions_.clear();
185 query_end_functions_.clear();
186}
187
189{
190 pre_event_functions_.push_back(func);
191}
192
197
202
207
212
217
219{
220 if (moveit_cpp_->getPlanningPipelines().empty())
221 {
222 RCLCPP_ERROR(getLogger(), "No planning pipelines configured. Did you call BenchmarkExecutor::initialize?");
223 return false;
224 }
225
226 std::vector<BenchmarkRequest> queries;
227 moveit_msgs::msg::PlanningScene scene_msg;
228
229 if (initializeBenchmarks(options, scene_msg, queries))
230 {
231 for (std::size_t i = 0; i < queries.size(); ++i)
232 {
233 // Configure planning scene
234 if (scene_msg.robot_model_name != planning_scene_->getRobotModel()->getName())
235 {
236 // Clear all geometry from the scene
237 planning_scene_->getWorldNonConst()->clearObjects();
238 planning_scene_->getCurrentStateNonConst().clearAttachedBodies();
239 planning_scene_->getCurrentStateNonConst().setToDefaultValues();
240
241 planning_scene_->processPlanningSceneWorldMsg(scene_msg.world);
242 }
243 else
244 {
245 planning_scene_->usePlanningSceneMsg(scene_msg);
246 }
247
248 // Calling query start events
249 for (QueryStartEventFunction& query_start_fn : query_start_functions_)
250 {
251 query_start_fn(queries[i].request, planning_scene_);
252 }
253
254 RCLCPP_INFO(getLogger(), "Benchmarking query '%s' (%lu of %lu)", queries[i].name.c_str(), i + 1, queries.size());
255 std::chrono::system_clock::time_point start_time = std::chrono::system_clock::now();
256 runBenchmark(queries[i].request, options);
257 std::chrono::duration<double> dt = std::chrono::system_clock::now() - start_time;
258 double duration = dt.count();
259
261 {
262 query_end_fn(queries[i].request, planning_scene_);
263 }
264
265 writeOutput(queries[i], boost::posix_time::to_iso_extended_string(toBoost(start_time)), duration, options);
266 }
267
268 return true;
269 }
270 return false;
271}
272
274 moveit_msgs::msg::PlanningScene& scene_msg,
275 std::vector<BenchmarkRequest>& requests)
276{
277 if (!pipelinesExist(options.planning_pipelines))
278 {
279 return false;
280 }
281
282 std::vector<StartState> start_states;
283 std::vector<PathConstraints> path_constraints;
284 std::vector<PathConstraints> goal_constraints;
285 std::vector<TrajectoryConstraints> traj_constraints;
286 std::vector<BenchmarkRequest> queries;
287
288 if (!loadBenchmarkQueryData(options, scene_msg, start_states, path_constraints, goal_constraints, traj_constraints,
289 queries))
290 {
291 RCLCPP_ERROR(getLogger(), "Failed to load benchmark query data");
292 return false;
293 }
294
295 RCLCPP_INFO(
296 getLogger(),
297 "Benchmark loaded %lu starts, %lu goals, %lu path constraints, %lu trajectory constraints, and %lu queries",
298 start_states.size(), goal_constraints.size(), path_constraints.size(), traj_constraints.size(), queries.size());
299
300 moveit_msgs::msg::WorkspaceParameters workspace_parameters = options.workspace;
301 // Make sure that workspace_parameters are set
302 if (workspace_parameters.min_corner.x == workspace_parameters.max_corner.x &&
303 workspace_parameters.min_corner.x == 0.0 &&
304 workspace_parameters.min_corner.y == workspace_parameters.max_corner.y &&
305 workspace_parameters.min_corner.y == 0.0 &&
306 workspace_parameters.min_corner.z == workspace_parameters.max_corner.z &&
307 workspace_parameters.min_corner.z == 0.0)
308 {
309 workspace_parameters.min_corner.x = workspace_parameters.min_corner.y = workspace_parameters.min_corner.z = -5.0;
310
311 workspace_parameters.max_corner.x = workspace_parameters.max_corner.y = workspace_parameters.max_corner.z = 5.0;
312 }
313
314 // Create the combinations of BenchmarkRequests
315
316 // 1) Create requests for combinations of start states,
317 // goal constraints, and path constraints
318 for (PathConstraints& goal_constraint : goal_constraints)
319 {
320 // Common benchmark request properties
321 BenchmarkRequest benchmark_request;
322 benchmark_request.name = goal_constraint.name;
323 benchmark_request.request.workspace_parameters = workspace_parameters;
324 benchmark_request.request.goal_constraints = goal_constraint.constraints;
325 benchmark_request.request.group_name = options.group_name;
326 benchmark_request.request.allowed_planning_time = options.timeout;
327 benchmark_request.request.num_planning_attempts = 1;
328
329 if (benchmark_request.request.goal_constraints.size() == 1 &&
330 benchmark_request.request.goal_constraints.at(0).position_constraints.size() == 1 &&
331 benchmark_request.request.goal_constraints.at(0).orientation_constraints.size() == 1 &&
332 benchmark_request.request.goal_constraints.at(0).visibility_constraints.empty() &&
333 benchmark_request.request.goal_constraints.at(0).joint_constraints.empty())
334 {
335 shiftConstraintsByOffset(benchmark_request.request.goal_constraints.at(0), options.goal_offsets);
336 }
337
338 std::vector<BenchmarkRequest> request_combos;
339 createRequestCombinations(benchmark_request, start_states, path_constraints, request_combos);
340 requests.insert(requests.end(), request_combos.begin(), request_combos.end());
341 }
342
343 // 2) Existing queries are treated like goal constraints.
344 // Create all combos of query, start states, and path constraints
345 for (BenchmarkRequest& query : queries)
346 {
347 // Common benchmark request properties
348 BenchmarkRequest benchmark_request;
349 benchmark_request.name = query.name;
350 benchmark_request.request = query.request;
351 benchmark_request.request.group_name = options.group_name;
352 benchmark_request.request.allowed_planning_time = options.timeout;
353 benchmark_request.request.num_planning_attempts = 1;
354
355 // Make sure that workspace_parameters are set
356 if (benchmark_request.request.workspace_parameters.min_corner.x ==
357 benchmark_request.request.workspace_parameters.max_corner.x &&
358 benchmark_request.request.workspace_parameters.min_corner.x == 0.0 &&
359 benchmark_request.request.workspace_parameters.min_corner.y ==
360 benchmark_request.request.workspace_parameters.max_corner.y &&
361 benchmark_request.request.workspace_parameters.min_corner.y == 0.0 &&
362 benchmark_request.request.workspace_parameters.min_corner.z ==
363 benchmark_request.request.workspace_parameters.max_corner.z &&
364 benchmark_request.request.workspace_parameters.min_corner.z == 0.0)
365 {
366 // ROS_WARN("Workspace parameters are not set for request %s. Setting defaults", queries[i].name.c_str());
367 benchmark_request.request.workspace_parameters = workspace_parameters;
368 }
369
370 // Create all combinations of start states and path constraints
371 std::vector<BenchmarkRequest> request_combos;
372 createRequestCombinations(benchmark_request, start_states, path_constraints, request_combos);
373 requests.insert(requests.end(), request_combos.begin(), request_combos.end());
374 }
375
376 // 3) Trajectory constraints are also treated like goal constraints
377 for (TrajectoryConstraints& traj_constraint : traj_constraints)
378 {
379 // Common benchmark request properties
380 BenchmarkRequest benchmark_request;
381 benchmark_request.name = traj_constraint.name;
382 benchmark_request.request.trajectory_constraints = traj_constraint.constraints;
383 benchmark_request.request.group_name = options.group_name;
384 benchmark_request.request.allowed_planning_time = options.timeout;
385 benchmark_request.request.num_planning_attempts = 1;
386
387 if (benchmark_request.request.trajectory_constraints.constraints.size() == 1 &&
388 benchmark_request.request.trajectory_constraints.constraints.at(0).position_constraints.size() == 1 &&
389 benchmark_request.request.trajectory_constraints.constraints.at(0).orientation_constraints.size() == 1 &&
390 benchmark_request.request.trajectory_constraints.constraints.at(0).visibility_constraints.empty() &&
391 benchmark_request.request.trajectory_constraints.constraints.at(0).joint_constraints.empty())
392 {
393 shiftConstraintsByOffset(benchmark_request.request.trajectory_constraints.constraints.at(0), options.goal_offsets);
394 }
395
396 std::vector<BenchmarkRequest> request_combos;
397 std::vector<PathConstraints> no_path_constraints;
398 createRequestCombinations(benchmark_request, start_states, no_path_constraints, request_combos);
399 requests.insert(requests.end(), request_combos.begin(), request_combos.end());
400 }
401 return true;
402}
403
405 const BenchmarkOptions& options, moveit_msgs::msg::PlanningScene& scene_msg, std::vector<StartState>& start_states,
406 std::vector<PathConstraints>& path_constraints, std::vector<PathConstraints>& goal_constraints,
407 std::vector<TrajectoryConstraints>& traj_constraints, std::vector<BenchmarkRequest>& queries)
408{
409 try
410 {
411 warehouse_ros::DatabaseConnection::Ptr warehouse_connection = db_loader_.loadDatabase();
412 warehouse_connection->setParams(options.hostname, options.port, 20);
413 if (warehouse_connection->connect())
414 {
415 planning_scene_storage_ = std::make_shared<moveit_warehouse::PlanningSceneStorage>(warehouse_connection);
417 std::make_shared<moveit_warehouse::PlanningSceneWorldStorage>(warehouse_connection);
418 robot_state_storage_ = std::make_shared<moveit_warehouse::RobotStateStorage>(warehouse_connection);
419 constraints_storage_ = std::make_shared<moveit_warehouse::ConstraintsStorage>(warehouse_connection);
421 std::make_shared<moveit_warehouse::TrajectoryConstraintsStorage>(warehouse_connection);
422 RCLCPP_INFO(getLogger(), "Connected to DB");
423 }
424 else
425 {
426 RCLCPP_ERROR(getLogger(), "Failed to connect to DB");
427 return false;
428 }
429 }
430 catch (std::exception& e)
431 {
432 RCLCPP_ERROR(getLogger(), "Failed to initialize benchmark server: '%s'", e.what());
433 return false;
434 }
435
436 if (!loadPlanningScene(options.scene_name, scene_msg))
437 {
438 RCLCPP_ERROR(getLogger(), "Failed to load the planning scene");
439 return false;
440 }
441 if (!loadStates(options.start_state_regex, start_states))
442 {
443 RCLCPP_ERROR(getLogger(), "Failed to load the states");
444 return false;
445 }
446 if (!loadPathConstraints(options.goal_constraint_regex, goal_constraints))
447 {
448 RCLCPP_ERROR(getLogger(), "Failed to load the goal constraints");
449 }
450 if (!loadPathConstraints(options.path_constraint_regex, path_constraints))
451 {
452 RCLCPP_ERROR(getLogger(), "Failed to load the path constraints");
453 }
454 if (!loadTrajectoryConstraints(options.trajectory_constraint_regex, traj_constraints))
455 {
456 RCLCPP_ERROR(getLogger(), "Failed to load the trajectory constraints");
457 }
458 if (!loadQueries(options.query_regex, options.scene_name, queries))
459 {
460 RCLCPP_ERROR(getLogger(), "Failed to get a query regex");
461 }
462 return true;
463}
464
465void BenchmarkExecutor::shiftConstraintsByOffset(moveit_msgs::msg::Constraints& constraints,
466 const std::vector<double>& offset)
467{
468 Eigen::Isometry3d offset_tf(Eigen::AngleAxis<double>(offset.at(3), Eigen::Vector3d::UnitX()) *
469 Eigen::AngleAxis<double>(offset.at(4), Eigen::Vector3d::UnitY()) *
470 Eigen::AngleAxis<double>(offset.at(5), Eigen::Vector3d::UnitZ()));
471 offset_tf.translation() = Eigen::Vector3d(offset.at(0), offset.at(1), offset.at(2));
472
473 geometry_msgs::msg::Pose constraint_pose_msg;
474 constraint_pose_msg.position =
475 constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).position;
476 constraint_pose_msg.orientation = constraints.orientation_constraints.at(0).orientation;
477 Eigen::Isometry3d constraint_pose;
478 tf2::fromMsg(constraint_pose_msg, constraint_pose);
479
480 Eigen::Isometry3d new_pose = constraint_pose * offset_tf;
481 geometry_msgs::msg::Pose new_pose_msg;
482 new_pose_msg = tf2::toMsg(new_pose);
483
484 constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).position = new_pose_msg.position;
485 constraints.orientation_constraints.at(0).orientation = new_pose_msg.orientation;
486}
487
489 const std::vector<StartState>& start_states,
490 const std::vector<PathConstraints>& path_constraints,
491 std::vector<BenchmarkRequest>& requests)
492{
493 // Use default start state
494 if (start_states.empty())
495 {
496 // Adding path constraints
497 for (const PathConstraints& path_constraint : path_constraints)
498 {
499 BenchmarkRequest new_benchmark_request = benchmark_request;
500 new_benchmark_request.request.path_constraints = path_constraint.constraints.at(0);
501 new_benchmark_request.name = benchmark_request.name + "_" + path_constraint.name;
502 requests.push_back(new_benchmark_request);
503 }
504
505 if (path_constraints.empty())
506 {
507 requests.push_back(benchmark_request);
508 }
509 }
510 else // Create a request for each start state specified
511 {
512 for (const StartState& start_state : start_states)
513 {
514 // Skip start states that have the same name as the goal
515 if (start_state.name == benchmark_request.name)
516 continue;
517
518 BenchmarkRequest new_benchmark_request = benchmark_request;
519 new_benchmark_request.request.start_state = start_state.state;
520
521 // Duplicate the request for each of the path constraints
522 for (const PathConstraints& path_constraint : path_constraints)
523 {
524 new_benchmark_request.request.path_constraints = path_constraint.constraints.at(0);
525 new_benchmark_request.name = start_state.name + "_" + new_benchmark_request.name + "_" + path_constraint.name;
526 requests.push_back(new_benchmark_request);
527 }
528
529 if (path_constraints.empty())
530 {
531 new_benchmark_request.name = start_state.name + "_" + benchmark_request.name;
532 requests.push_back(new_benchmark_request);
533 }
534 }
535 }
536}
537
538bool BenchmarkExecutor::pipelinesExist(const std::map<std::string, std::vector<std::string>>& pipeline_configurations)
539{
540 // Make sure planner plugins exist
541 for (const std::pair<const std::string, std::vector<std::string>>& pipeline_config_entry : pipeline_configurations)
542 {
543 bool pipeline_exists = false;
544 for (const std::pair<const std::string, planning_pipeline::PlanningPipelinePtr>& pipeline_entry :
545 moveit_cpp_->getPlanningPipelines())
546 {
547 pipeline_exists = pipeline_entry.first == pipeline_config_entry.first;
548 if (pipeline_exists)
549 break;
550 }
551
552 if (!pipeline_exists)
553 {
554 RCLCPP_ERROR(getLogger(), "Planning pipeline '%s' does NOT exist", pipeline_config_entry.first.c_str());
555 return false;
556 }
557 }
558 return true;
559}
560
561bool BenchmarkExecutor::loadPlanningScene(const std::string& scene_name, moveit_msgs::msg::PlanningScene& scene_msg)
562{
563 try
564 {
565 if (planning_scene_storage_->hasPlanningScene(scene_name)) // whole planning scene
566 {
567 moveit_warehouse::PlanningSceneWithMetadata planning_scene_w_metadata;
568
569 if (!planning_scene_storage_->getPlanningScene(planning_scene_w_metadata, scene_name))
570 {
571 RCLCPP_ERROR(getLogger(), "Failed to load planning scene '%s'", scene_name.c_str());
572 return false;
573 }
574 scene_msg = static_cast<moveit_msgs::msg::PlanningScene>(*planning_scene_w_metadata);
575 }
576 else if (planning_scene_world_storage_->hasPlanningSceneWorld(scene_name)) // Just the world (no robot)
577 {
579 if (!planning_scene_world_storage_->getPlanningSceneWorld(pswwm, scene_name))
580 {
581 RCLCPP_ERROR(getLogger(), "Failed to load planning scene world '%s'", scene_name.c_str());
582 return false;
583 }
584 scene_msg.world = static_cast<moveit_msgs::msg::PlanningSceneWorld>(*pswwm);
585 scene_msg.robot_model_name =
586 "NO ROBOT INFORMATION. ONLY WORLD GEOMETRY"; // this will be fixed when running benchmark
587 }
588 else
589 {
590 RCLCPP_ERROR(getLogger(), "Failed to find planning scene '%s'", scene_name.c_str());
591 return false;
592 }
593 }
594 catch (std::exception& ex)
595 {
596 RCLCPP_ERROR(getLogger(), "Error loading planning scene: %s", ex.what());
597 return false;
598 }
599 RCLCPP_INFO(getLogger(), "Loaded planning scene successfully");
600 return true;
601}
602
603bool BenchmarkExecutor::loadQueries(const std::string& regex, const std::string& scene_name,
604 std::vector<BenchmarkRequest>& queries)
605{
606 if (regex.empty())
607 {
608 RCLCPP_WARN(getLogger(), "No query regex provided, don't load any queries from the database");
609 return true;
610 }
611
612 std::vector<std::string> query_names;
613 try
614 {
615 planning_scene_storage_->getPlanningQueriesNames(regex, query_names, scene_name);
616 }
617 catch (std::exception& ex)
618 {
619 RCLCPP_ERROR(getLogger(), "Error loading motion planning queries: %s", ex.what());
620 return false;
621 }
622
623 if (query_names.empty())
624 {
625 RCLCPP_ERROR(getLogger(), "Scene '%s' has no associated queries", scene_name.c_str());
626 return false;
627 }
628
629 for (const std::string& query_name : query_names)
630 {
632 try
633 {
634 planning_scene_storage_->getPlanningQuery(planning_query, scene_name, query_name);
635 }
636 catch (std::exception& ex)
637 {
638 RCLCPP_ERROR(getLogger(), "Error loading motion planning query '%s': %s", query_name.c_str(), ex.what());
639 continue;
640 }
641
642 BenchmarkRequest query;
643 query.name = query_name;
644 query.request = static_cast<moveit_msgs::msg::MotionPlanRequest>(*planning_query);
645 queries.push_back(query);
646 }
647 RCLCPP_INFO(getLogger(), "Loaded queries successfully");
648 return true;
649}
650
651bool BenchmarkExecutor::loadStates(const std::string& regex, std::vector<StartState>& start_states)
652{
653 if (!regex.empty())
654 {
655 std::regex start_regex(regex);
656 std::vector<std::string> state_names;
657 robot_state_storage_->getKnownRobotStates(state_names);
658
659 if (state_names.empty())
660 {
661 RCLCPP_WARN(getLogger(), "Database does not contain any named states");
662 }
663
664 for (const std::string& state_name : state_names)
665 {
666 std::smatch match;
667 if (std::regex_match(state_name, match, start_regex))
668 {
670 try
671 {
672 if (robot_state_storage_->getRobotState(robot_state, state_name))
673 {
674 StartState start_state;
675 start_state.state = moveit_msgs::msg::RobotState(*robot_state);
676 start_state.name = state_name;
677 start_states.push_back(start_state);
678 }
679 }
680 catch (std::exception& ex)
681 {
682 RCLCPP_ERROR(getLogger(), "Runtime error when loading state '%s': %s", state_name.c_str(), ex.what());
683 continue;
684 }
685 }
686 }
687
688 if (start_states.empty())
689 {
690 RCLCPP_WARN(getLogger(), "No stored states matched the provided start state regex: '%s'", regex.c_str());
691 }
692 }
693 RCLCPP_INFO(getLogger(), "Loaded states successfully");
694 return true;
695}
696
697bool BenchmarkExecutor::loadPathConstraints(const std::string& regex, std::vector<PathConstraints>& constraints)
698{
699 if (!regex.empty())
700 {
701 std::vector<std::string> cnames;
702 constraints_storage_->getKnownConstraints(regex, cnames);
703
704 for (const std::string& cname : cnames)
705 {
707 try
708 {
709 if (constraints_storage_->getConstraints(constr, cname))
710 {
711 PathConstraints constraint;
712 constraint.constraints.push_back(*constr);
713 constraint.name = cname;
714 constraints.push_back(constraint);
715 }
716 }
717 catch (std::exception& ex)
718 {
719 RCLCPP_ERROR(getLogger(), "Runtime error when loading path constraint '%s': %s", cname.c_str(), ex.what());
720 continue;
721 }
722 }
723
724 if (constraints.empty())
725 {
726 RCLCPP_WARN(getLogger(), "No path constraints found that match regex: '%s'", regex.c_str());
727 }
728 else
729 {
730 RCLCPP_INFO(getLogger(), "Loaded path constraints successfully");
731 }
732 }
733 return true;
734}
735
737 std::vector<TrajectoryConstraints>& constraints)
738{
739 if (!regex.empty())
740 {
741 std::vector<std::string> cnames;
742 trajectory_constraints_storage_->getKnownTrajectoryConstraints(regex, cnames);
743
744 for (const std::string& cname : cnames)
745 {
747 try
748 {
749 if (trajectory_constraints_storage_->getTrajectoryConstraints(constr, cname))
750 {
751 TrajectoryConstraints constraint;
752 constraint.constraints = *constr;
753 constraint.name = cname;
754 constraints.push_back(constraint);
755 }
756 }
757 catch (std::exception& ex)
758 {
759 RCLCPP_ERROR(getLogger(), "Runtime error when loading trajectory constraint '%s': %s", cname.c_str(), ex.what());
760 continue;
761 }
762 }
763
764 if (constraints.empty())
765 {
766 RCLCPP_WARN(getLogger(), "No trajectory constraints found that match regex: '%s'", regex.c_str());
767 }
768 else
769 {
770 RCLCPP_INFO(getLogger(), "Loaded trajectory constraints successfully");
771 }
772 }
773 return true;
774}
775
776void BenchmarkExecutor::runBenchmark(moveit_msgs::msg::MotionPlanRequest request, const BenchmarkOptions& options)
777{
778 benchmark_data_.clear();
779
780 auto num_planners = 0;
781 for (const std::pair<const std::string, std::vector<std::string>>& pipeline_entry : options.planning_pipelines)
782 {
783 num_planners += pipeline_entry.second.size();
784 }
785 num_planners += options.parallel_planning_pipelines.size();
786
787 boost_progress_display progress(num_planners * options.runs, std::cout);
788
789 // Iterate through all planning pipelines
790 auto planning_pipelines = moveit_cpp_->getPlanningPipelines();
791 for (const std::pair<const std::string, std::vector<std::string>>& pipeline_entry : options.planning_pipelines)
792 {
793 // Iterate through all planners configured for the pipeline
794 for (const std::string& planner_id : pipeline_entry.second)
795 {
796 // This container stores all of the benchmark data for this planner
797 PlannerBenchmarkData planner_data(options.runs);
798 // This vector stores all motion plan results for further evaluation
799 std::vector<planning_interface::MotionPlanDetailedResponse> responses(options.runs);
800 std::vector<bool> solved(options.runs);
801
802 request.planner_id = planner_id;
803
804 // Planner start events
805 for (PlannerStartEventFunction& planner_start_function : planner_start_functions_)
806 {
807 planner_start_function(request, planner_data);
808 }
809
811 .planner_id = planner_id,
812 .planning_pipeline = pipeline_entry.first,
813 .planning_attempts = request.num_planning_attempts,
814 .planning_time = request.allowed_planning_time,
815 .max_velocity_scaling_factor = request.max_velocity_scaling_factor,
816 .max_acceleration_scaling_factor = request.max_acceleration_scaling_factor
817 };
818
819 // Iterate runs
820 for (int j = 0; j < options.runs; ++j)
821 {
822 // Pre-run events
823 for (PreRunEventFunction& pre_event_function : pre_event_functions_)
824 pre_event_function(request);
825
826 // Create planning component
827 auto planning_component = std::make_shared<moveit_cpp::PlanningComponent>(request.group_name, moveit_cpp_);
828 moveit::core::RobotState start_state(planning_scene_monitor_->getRobotModel());
829 moveit::core::robotStateMsgToRobotState(request.start_state, start_state);
830
831 planning_component->setStartState(start_state);
832 planning_component->setGoal(request.goal_constraints);
833 planning_component->setPathConstraints(request.path_constraints);
834 planning_component->setTrajectoryConstraints(request.trajectory_constraints);
835
836 // Solve problem
837 std::chrono::system_clock::time_point start = std::chrono::system_clock::now();
838
839 // Planning pipeline benchmark
840 const auto response = planning_component->plan(plan_req_params, planning_scene_);
841
842 solved[j] = bool(response.error_code);
843
844 responses[j].error_code = response.error_code;
845 if (response.trajectory)
846 {
847 responses[j].description.push_back("plan");
848 responses[j].trajectory.push_back(response.trajectory);
849 responses[j].processing_time.push_back(response.planning_time);
850 }
851
852 std::chrono::duration<double> dt = std::chrono::system_clock::now() - start;
853 double total_time = dt.count();
854
855 // Collect data
856 start = std::chrono::system_clock::now();
857
858 // Post-run events
859 for (PostRunEventFunction& post_event_fn : post_event_functions_)
860 {
861 post_event_fn(request, responses[j], planner_data[j]);
862 }
863 collectMetrics(planner_data[j], responses[j], solved[j], total_time);
864 dt = std::chrono::system_clock::now() - start;
865 double metriconstraints_storage_time = dt.count();
866 RCLCPP_DEBUG(getLogger(), "Spent %lf seconds collecting metrics", metriconstraints_storage_time);
867
868 ++progress;
869 }
870
871 computeAveragePathSimilarities(planner_data, responses, solved);
872
873 // Planner completion events
875 {
876 planner_completion_fn(request, planner_data);
877 }
878
879 benchmark_data_.push_back(planner_data);
880 }
881 }
882
883 if (!options.parallel_planning_pipelines.empty())
884 {
885 // Iterate through all parallel pipelines
886 for (const std::pair<const std::string, std::vector<std::pair<std::string, std::string>>>& parallel_pipeline_entry :
887 options.parallel_planning_pipelines)
888 {
889 // This container stores all of the benchmark data for this planner
890 PlannerBenchmarkData planner_data(options.runs);
891 // This vector stores all motion plan results for further evaluation
892 std::vector<planning_interface::MotionPlanDetailedResponse> responses(options.runs);
893 std::vector<bool> solved(options.runs);
894
895 // Planner start events
896 for (PlannerStartEventFunction& planner_start_function : planner_start_functions_)
897 {
898 planner_start_function(request, planner_data);
899 }
900
901 // Create multi-pipeline request
903 for (const auto& pipeline_planner_id_pair : parallel_pipeline_entry.second)
904 {
906 .planner_id = pipeline_planner_id_pair.second,
907 .planning_pipeline = pipeline_planner_id_pair.first,
908 .planning_attempts = request.num_planning_attempts,
909 .planning_time = request.allowed_planning_time,
910 .max_velocity_scaling_factor = request.max_velocity_scaling_factor,
911 .max_acceleration_scaling_factor = request.max_acceleration_scaling_factor
912 };
913 multi_pipeline_plan_request.plan_request_parameter_vector.push_back(plan_req_params);
914 }
915
916 // Iterate runs
917 for (int j = 0; j < options.runs; ++j)
918 {
919 // Pre-run events
920 for (PreRunEventFunction& pre_event_function : pre_event_functions_)
921 {
922 pre_event_function(request);
923 }
924
925 // Create planning component
926 auto planning_component = std::make_shared<moveit_cpp::PlanningComponent>(request.group_name, moveit_cpp_);
927 moveit::core::RobotState start_state(planning_scene_monitor_->getRobotModel());
928 moveit::core::robotStateMsgToRobotState(request.start_state, start_state);
929
930 planning_component->setStartState(start_state);
931 planning_component->setGoal(request.goal_constraints);
932 planning_component->setPathConstraints(request.path_constraints);
933 planning_component->setTrajectoryConstraints(request.trajectory_constraints);
934
935 // Solve problem
936 std::chrono::system_clock::time_point start = std::chrono::system_clock::now();
937
938 const auto t1 = std::chrono::system_clock::now();
939 const auto response = planning_component->plan(multi_pipeline_plan_request,
941 nullptr, planning_scene_);
942 const auto t2 = std::chrono::system_clock::now();
943
944 solved[j] = bool(response.error_code);
945
946 responses[j].error_code = response.error_code;
947 if (response.trajectory)
948 {
949 responses[j].description.push_back("plan");
950 responses[j].trajectory.push_back(response.trajectory);
951 responses[j].processing_time.push_back(std::chrono::duration_cast<std::chrono::milliseconds>(t2 - t1).count());
952 }
953
954 std::chrono::duration<double> dt = std::chrono::system_clock::now() - start;
955 double total_time = dt.count();
956
957 // Collect data
958 start = std::chrono::system_clock::now();
959 // Post-run events
960 for (PostRunEventFunction& post_event_fn : post_event_functions_)
961 {
962 post_event_fn(request, responses[j], planner_data[j]);
963 }
964
965 collectMetrics(planner_data[j], responses[j], solved[j], total_time);
966 dt = std::chrono::system_clock::now() - start;
967 double metriconstraints_storage_time = dt.count();
968 RCLCPP_DEBUG(getLogger(), "Spent %lf seconds collecting metrics", metriconstraints_storage_time);
969
970 ++progress;
971 }
972
973 computeAveragePathSimilarities(planner_data, responses, solved);
974
975 // Planner completion events
977 {
978 planner_completion_fn(request, planner_data);
979 }
980
981 benchmark_data_.push_back(planner_data);
982 }
983 }
984}
985
987 const planning_interface::MotionPlanDetailedResponse& motion_plan_response,
988 bool solved, double total_time)
989{
990 metrics["time REAL"] = moveit::core::toString(total_time);
991 metrics["solved BOOLEAN"] = solved ? "true" : "false";
992
993 if (solved)
994 {
995 // Analyzing the trajectory(ies) geometrically
996 double traj_len = 0.0; // trajectory length
997 double clearance = 0.0; // trajectory clearance (average)
998 bool correct = true; // entire trajectory collision free and in bounds
999
1000 double process_time = total_time;
1001 for (std::size_t j = 0; j < motion_plan_response.trajectory.size(); ++j)
1002 {
1003 correct = true;
1004 traj_len = 0.0;
1005 clearance = 0.0;
1006 const robot_trajectory::RobotTrajectory& p = *motion_plan_response.trajectory[j];
1007
1008 // compute path length
1009 traj_len = robot_trajectory::pathLength(p);
1010
1011 // compute correctness and clearance
1013 for (std::size_t k = 0; k < p.getWayPointCount(); ++k)
1014 {
1016 planning_scene_->checkCollisionUnpadded(req, res, p.getWayPoint(k));
1017 if (res.collision)
1018 correct = false;
1019 if (!p.getWayPoint(k).satisfiesBounds())
1020 correct = false;
1021 double d = planning_scene_->distanceToCollisionUnpadded(p.getWayPoint(k));
1022 if (d > 0.0) // in case of collision, distance is negative
1023 clearance += d;
1024 }
1025 clearance /= static_cast<double>(p.getWayPointCount());
1026
1027 // compute smoothness
1028 const auto smoothness = [&]() {
1029 const auto s = robot_trajectory::smoothness(p);
1030 return s.has_value() ? s.value() : 0.0;
1031 }();
1032
1033 metrics["path_" + motion_plan_response.description[j] + "_correct BOOLEAN"] = correct ? "true" : "false";
1034 metrics["path_" + motion_plan_response.description[j] + "_length REAL"] = moveit::core::toString(traj_len);
1035 metrics["path_" + motion_plan_response.description[j] + "_clearance REAL"] = moveit::core::toString(clearance);
1036 metrics["path_" + motion_plan_response.description[j] + "_smoothness REAL"] = moveit::core::toString(smoothness);
1037 metrics["path_" + motion_plan_response.description[j] + "_time REAL"] =
1038 moveit::core::toString(motion_plan_response.processing_time[j]);
1039
1040 if (j == motion_plan_response.trajectory.size() - 1)
1041 {
1042 metrics["final_path_correct BOOLEAN"] = correct ? "true" : "false";
1043 metrics["final_path_length REAL"] = moveit::core::toString(traj_len);
1044 metrics["final_path_clearance REAL"] = moveit::core::toString(clearance);
1045 metrics["final_path_smoothness REAL"] = moveit::core::toString(smoothness);
1046 metrics["final_path_time REAL"] = moveit::core::toString(motion_plan_response.processing_time[j]);
1047 }
1048 process_time -= motion_plan_response.processing_time[j];
1049 }
1050 if (process_time <= 0.0)
1051 process_time = 0.0;
1052 metrics["process_time REAL"] = moveit::core::toString(process_time);
1053 }
1054}
1055
1057 PlannerBenchmarkData& planner_data, const std::vector<planning_interface::MotionPlanDetailedResponse>& responses,
1058 const std::vector<bool>& solved)
1059{
1060 RCLCPP_INFO(getLogger(), "Computing result path similarity");
1061 const size_t result_count = planner_data.size();
1062 size_t unsolved = std::count_if(solved.begin(), solved.end(), [](bool s) { return !s; });
1063 std::vector<double> average_distances(responses.size());
1064 for (size_t first_traj_i = 0; first_traj_i < result_count; ++first_traj_i)
1065 {
1066 // If trajectory was not solved there is no valid average distance so it's set to max double only
1067 if (!solved[first_traj_i])
1068 {
1069 average_distances[first_traj_i] = std::numeric_limits<double>::max();
1070 continue;
1071 }
1072 // Iterate all result trajectories that haven't been compared yet
1073 for (size_t second_traj_i = first_traj_i + 1; second_traj_i < result_count; ++second_traj_i)
1074 {
1075 // Ignore if other result has not been solved
1076 if (!solved[second_traj_i])
1077 continue;
1078
1079 // Get final trajectories
1080 const robot_trajectory::RobotTrajectory& traj_first = *responses[first_traj_i].trajectory.back();
1081 const robot_trajectory::RobotTrajectory& traj_second = *responses[second_traj_i].trajectory.back();
1082
1083 // Compute trajectory distance
1084 double trajectory_distance;
1085 if (!computeTrajectoryDistance(traj_first, traj_second, trajectory_distance))
1086 continue;
1087
1088 // Add average distance to counters of both trajectories
1089 average_distances[first_traj_i] += trajectory_distance;
1090 average_distances[second_traj_i] += trajectory_distance;
1091 }
1092 // Normalize average distance by number of actual comparisons
1093 average_distances[first_traj_i] /= result_count - unsolved - 1;
1094 }
1095
1096 // Store results in planner_data
1097 for (size_t i = 0; i < result_count; ++i)
1098 planner_data[i]["average_waypoint_distance REAL"] = moveit::core::toString(average_distances[i]);
1099}
1100
1102 const robot_trajectory::RobotTrajectory& traj_second,
1103 double& result_distance)
1104{
1105 // Abort if trajectories are empty
1106 if (traj_first.empty() || traj_second.empty())
1107 return false;
1108
1109 // Waypoint counter
1110 size_t pos_first = 0;
1111 size_t pos_second = 0;
1112 const size_t max_pos_first = traj_first.getWayPointCount() - 1;
1113 const size_t max_pos_second = traj_second.getWayPointCount() - 1;
1114
1115 // Compute total distance between pairwise waypoints of both trajectories.
1116 // The selection of waypoint pairs is based on what steps results in the minimal distance between the next pair of
1117 // waypoints. We first check what steps are still possible or if we reached the end of the trajectories. Then we
1118 // compute the pairwise waypoint distances of the pairs from increasing both, the first, or the second trajectory.
1119 // Finally we select the pair that results in the minimal distance, summarize the total distance and iterate
1120 // accordingly. After that we compute the average trajectory distance by normalizing over the number of steps.
1121 double total_distance = 0;
1122 size_t steps = 0;
1123 double current_distance = traj_first.getWayPoint(pos_first).distance(traj_second.getWayPoint(pos_second));
1124 while (true)
1125 {
1126 // Keep track of total distance and number of comparisons
1127 total_distance += current_distance;
1128 ++steps;
1129 if (pos_first == max_pos_first && pos_second == max_pos_second) // end reached
1130 break;
1131
1132 // Determine what steps are still possible
1133 bool can_up_first = pos_first < max_pos_first;
1134 bool can_up_second = pos_second < max_pos_second;
1135 bool can_up_both = can_up_first && can_up_second;
1136
1137 // Compute pair-wise waypoint distances (increasing both, first, or second trajectories).
1138 double up_both = std::numeric_limits<double>::max();
1139 double up_first = std::numeric_limits<double>::max();
1140 double up_second = std::numeric_limits<double>::max();
1141 if (can_up_both)
1142 up_both = traj_first.getWayPoint(pos_first + 1).distance(traj_second.getWayPoint(pos_second + 1));
1143 if (can_up_first)
1144 up_first = traj_first.getWayPoint(pos_first + 1).distance(traj_second.getWayPoint(pos_second));
1145 if (can_up_second)
1146 up_second = traj_first.getWayPoint(pos_first).distance(traj_second.getWayPoint(pos_second + 1));
1147
1148 // Select actual step, store new distance value and iterate trajectory positions
1149 if (can_up_both && up_both < up_first && up_both < up_second)
1150 {
1151 ++pos_first;
1152 ++pos_second;
1153 current_distance = up_both;
1154 }
1155 else if ((can_up_first && up_first < up_second) || !can_up_second)
1156 {
1157 ++pos_first;
1158 current_distance = up_first;
1159 }
1160 else if (can_up_second)
1161 {
1162 ++pos_second;
1163 current_distance = up_second;
1164 }
1165 }
1166 // Normalize trajectory distance by number of comparison steps
1167 result_distance = total_distance / static_cast<double>(steps);
1168 return true;
1169}
1170
1171void BenchmarkExecutor::writeOutput(const BenchmarkRequest& benchmark_request, const std::string& start_time,
1172 double benchmark_duration, const BenchmarkOptions& options)
1173{
1174 // Count number of benchmarked planners
1175 size_t num_planners = 0;
1176 for (const std::pair<const std::string, std::vector<std::string>>& pipeline : options.planning_pipelines)
1177 {
1178 num_planners += pipeline.second.size();
1179 }
1180 num_planners += options.parallel_planning_pipelines.size();
1181
1182 std::string hostname = [&]() {
1183 static const int BUF_SIZE = 1024;
1184 char buffer[BUF_SIZE];
1185 int err = gethostname(buffer, sizeof(buffer));
1186 if (err != 0)
1187 {
1188 return std::string();
1189 }
1190 else
1191 {
1192 buffer[BUF_SIZE - 1] = '\0';
1193 return std::string(buffer);
1194 }
1195 }();
1196 if (hostname.empty())
1197 {
1198 hostname = "UNKNOWN";
1199 }
1200
1201 // Set output directory name
1202 std::string filename = options.output_directory;
1203 if (!filename.empty() && filename[filename.size() - 1] != '/')
1204 {
1205 filename.append("/");
1206 }
1207
1208 // Ensure directories exist
1209 std::filesystem::create_directories(filename);
1210
1211 // Create output log file name
1212 filename += (options.benchmark_name.empty() ? "" : options.benchmark_name + "_") + benchmark_request.name + "_" +
1213 hostname + "_" + start_time + ".log";
1214
1215 // Write benchmark results to file
1216 std::ofstream out(filename.c_str());
1217 if (!out)
1218 {
1219 RCLCPP_ERROR(getLogger(), "Failed to open '%s' for benchmark output", filename.c_str());
1220 return;
1221 }
1222
1223 // General data
1224 out << "MoveIt version " << MOVEIT_VERSION_STR << '\n';
1225 out << "Experiment " << benchmark_request.name << '\n';
1226 out << "Running on " << hostname << '\n';
1227 out << "Starting at " << start_time << '\n';
1228
1229 // Experiment setup
1230 moveit_msgs::msg::PlanningScene scene_msg;
1231 planning_scene_->getPlanningSceneMsg(scene_msg);
1232 out << "<<<|" << '\n';
1233 out << "Motion plan request:" << '\n'
1234 << " planner_id: " << benchmark_request.request.planner_id << '\n'
1235 << " group_name: " << benchmark_request.request.group_name << '\n'
1236 << " num_planning_attempts: " << benchmark_request.request.num_planning_attempts << '\n'
1237 << " allowed_planning_time: " << benchmark_request.request.allowed_planning_time << '\n';
1238 out << "Planning scene:" << '\n'
1239 << " scene_name: " << scene_msg.name << '\n'
1240 << " robot_model_name: " << scene_msg.robot_model_name << '\n'
1241 << "|>>>" << '\n';
1242
1243 // The real random seed is unknown. Writing a fake value
1244 out << "0 is the random seed" << '\n';
1245 out << benchmark_request.request.allowed_planning_time << " seconds per run" << '\n';
1246 // There is no memory cap
1247 out << "-1 MB per run" << '\n';
1248 out << options.runs << " runs per planner" << '\n';
1249 out << benchmark_duration << " seconds spent to collect the data" << '\n';
1250
1251 // No enum types
1252 out << "0 enum types" << '\n';
1253
1254 out << num_planners << " planners" << '\n';
1255
1256 // Index for benchmark data of one planner
1257 size_t run_id = 0;
1258
1259 // Write data for individual planners to the output file
1260 for (const std::pair<const std::string, std::vector<std::string>>& pipeline : options.planning_pipelines)
1261 {
1262 for (std::size_t i = 0; i < pipeline.second.size(); ++i, ++run_id)
1263 {
1264 // Write the name of the planner and the used pipeline
1265 out << pipeline.second[i] << " (" << pipeline.first << ')' << '\n';
1266
1267 // in general, we could have properties specific for a planner;
1268 // right now, we do not include such properties
1269 out << "0 common properties" << '\n';
1270
1271 // Create a list of the benchmark properties for this planner
1272 std::set<std::string> properties_set;
1273 for (PlannerRunData& planner_run_data : benchmark_data_[run_id])
1274 { // each run of this planner
1275 for (PlannerRunData::const_iterator pit = planner_run_data.begin(); pit != planner_run_data.end();
1276 ++pit) // each benchmark property of the given run
1277 properties_set.insert(pit->first);
1278 }
1279
1280 // Writing property list
1281 out << properties_set.size() << " properties for each run" << '\n';
1282 for (const std::string& property : properties_set)
1283 out << property << '\n';
1284
1285 // Number of runs
1286 out << benchmark_data_[run_id].size() << " runs" << '\n';
1287
1288 // And the benchmark properties
1289 for (PlannerRunData& planner_run_data : benchmark_data_[run_id]) // each run of this planner
1290 {
1291 // Write out properties in the order we listed them above
1292 for (const std::string& property : properties_set)
1293 {
1294 // Make sure this run has this property
1295 PlannerRunData::const_iterator runit = planner_run_data.find(property);
1296 if (runit != planner_run_data.end())
1297 out << runit->second;
1298 out << "; ";
1299 }
1300 out << '\n'; // end of the run
1301 }
1302 out << '.' << '\n'; // end the planner
1303 }
1304 }
1305
1306 // Write results for parallel planning pipelines to output file
1307 for (const std::pair<const std::string, std::vector<std::pair<std::string, std::string>>>& parallel_pipeline :
1308 options.parallel_planning_pipelines)
1309 {
1310 // Write the name of the planner and the used pipeline
1311 out << parallel_pipeline.first << " (" << parallel_pipeline.first << ")" << '\n';
1312
1313 // in general, we could have properties specific for a planner;
1314 // right now, we do not include such properties
1315 out << "0 common properties" << '\n';
1316
1317 // Create a list of the benchmark properties for this planner
1318 std::set<std::string> properties_set;
1319 // each run of this planner
1320 for (PlannerRunData& planner_run_data : benchmark_data_[run_id])
1321 {
1322 for (PlannerRunData::const_iterator pit = planner_run_data.begin(); pit != planner_run_data.end(); ++pit)
1323 {
1324 properties_set.insert(pit->first);
1325 }
1326 }
1327
1328 // Writing property list
1329 out << properties_set.size() << " properties for each run" << '\n';
1330 for (const std::string& property : properties_set)
1331 out << property << '\n';
1332
1333 // Number of runs
1334 out << benchmark_data_[run_id].size() << " runs" << '\n';
1335
1336 // And the benchmark properties
1337 for (PlannerRunData& planner_run_data : benchmark_data_[run_id]) // each run of this planner
1338 {
1339 // Write out properties in the order we listed them above
1340 for (const std::string& property : properties_set)
1341 {
1342 // Make sure this run has this property
1343 PlannerRunData::const_iterator runit = planner_run_data.find(property);
1344 if (runit != planner_run_data.end())
1345 out << runit->second;
1346 out << "; ";
1347 }
1348 out << '\n'; // end of the run
1349 }
1350 out << "." << '\n'; // end the planner
1351
1352 // Increase index
1353 run_id += 1;
1354 }
1355
1356 out.close();
1357 RCLCPP_INFO(getLogger(), "Benchmark results saved to '%s'", filename.c_str());
1358}
boost::progress_display boost_progress_display
boost::posix_time::ptime toBoost(const std::chrono::time_point< Clock, Duration > &from)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
double distance(const RobotState &other) const
Return the sum of joint distances to "other" state. An L1 norm. Only considers active joints.
bool satisfiesBounds(double margin=0.0) const
bool loadPlanningScene(const std::string &scene_name, moveit_msgs::msg::PlanningScene &scene_msg)
Load the planning scene with the given name from the warehouse.
void computeAveragePathSimilarities(PlannerBenchmarkData &planner_data, const std::vector< planning_interface::MotionPlanDetailedResponse > &responses, const std::vector< bool > &solved)
bool pipelinesExist(const std::map< std::string, std::vector< std::string > > &planners)
Check that the desired planning pipelines exist.
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.
void createRequestCombinations(const BenchmarkRequest &benchmark_request, 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.
std::vector< PlannerRunData > PlannerBenchmarkData
Structure to hold information for a single planner's benchmark data.
planning_scene::PlanningScenePtr planning_scene_
std::vector< PlannerStartEventFunction > planner_start_functions_
warehouse_ros::DatabaseLoader db_loader_
bool computeTrajectoryDistance(const robot_trajectory::RobotTrajectory &traj_first, const robot_trajectory::RobotTrajectory &traj_second, double &result_distance)
void addQueryStartEvent(const QueryStartEventFunction &func)
std::shared_ptr< moveit_warehouse::ConstraintsStorage > constraints_storage_
std::shared_ptr< moveit_warehouse::PlanningSceneStorage > planning_scene_storage_
std::function< void(const moveit_msgs::msg::MotionPlanRequest &request, PlannerBenchmarkData &benchmark_data)> PlannerCompletionEventFunction
std::vector< QueryCompletionEventFunction > query_end_functions_
std::shared_ptr< moveit_warehouse::TrajectoryConstraintsStorage > trajectory_constraints_storage_
std::function< void(const moveit_msgs::msg::MotionPlanRequest &request, planning_scene::PlanningScenePtr)> QueryCompletionEventFunction
Definition of a query-end benchmark event function. Invoked after a query has finished benchmarking.
std::shared_ptr< moveit_cpp::MoveItCpp > moveit_cpp_
virtual void collectMetrics(PlannerRunData &metrics, const planning_interface::MotionPlanDetailedResponse &motion_plan_response, bool solved, double total_time)
std::vector< QueryStartEventFunction > query_start_functions_
bool loadPathConstraints(const std::string &regex, std::vector< PathConstraints > &constraints)
Load all constraints matching the given regular expression from the warehouse.
std::vector< PreRunEventFunction > pre_event_functions_
void runBenchmark(moveit_msgs::msg::MotionPlanRequest request, const BenchmarkOptions &options)
Execute the given motion plan request on the set of planners for the set number of runs.
void addPreRunEvent(const PreRunEventFunction &func)
BenchmarkExecutor(const rclcpp::Node::SharedPtr &node, const std::string &robot_description_param="robot_description")
virtual bool runBenchmarks(const BenchmarkOptions &options)
std::vector< PlannerBenchmarkData > benchmark_data_
virtual bool loadBenchmarkQueryData(const BenchmarkOptions &options, moveit_msgs::msg::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.
std::vector< PostRunEventFunction > post_event_functions_
virtual bool initializeBenchmarks(const BenchmarkOptions &options, moveit_msgs::msg::PlanningScene &scene_msg, std::vector< BenchmarkRequest > &queries)
void addPlannerCompletionEvent(const PlannerCompletionEventFunction &func)
std::shared_ptr< planning_scene_monitor::PlanningSceneMonitor > planning_scene_monitor_
void addPlannerStartEvent(const PlannerStartEventFunction &func)
void addQueryCompletionEvent(const QueryCompletionEventFunction &func)
bool loadStates(const std::string &regex, std::vector< StartState > &start_states)
Load all states matching the given regular expression from the warehouse.
std::function< void(const moveit_msgs::msg::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...
std::function< void(moveit_msgs::msg::MotionPlanRequest &request)> PreRunEventFunction
Definition of a pre-run benchmark event function. Invoked immediately before each planner calls solve...
std::vector< PlannerCompletionEventFunction > planner_completion_functions_
std::shared_ptr< moveit_warehouse::RobotStateStorage > robot_state_storage_
std::function< void(const moveit_msgs::msg::MotionPlanRequest &request, planning_scene::PlanningScenePtr)> QueryStartEventFunction
Definition of a query-start benchmark event function. Invoked before a new query is benchmarked.
virtual void writeOutput(const BenchmarkRequest &benchmark_request, const std::string &start_time, double benchmark_duration, const BenchmarkOptions &options)
bool initialize(const std::vector< std::string > &plugin_classes)
std::shared_ptr< moveit_warehouse::PlanningSceneWorldStorage > planning_scene_world_storage_
std::function< void(const moveit_msgs::msg::MotionPlanRequest &request, PlannerBenchmarkData &benchmark_data)> PlannerStartEventFunction
bool loadTrajectoryConstraints(const std::string &regex, std::vector< TrajectoryConstraints > &constraints)
Load all trajectory constraints from the warehouse that match the given regular expression.
void addPostRunEvent(const PostRunEventFunction &func)
void shiftConstraintsByOffset(moveit_msgs::msg::Constraints &constraints, const std::vector< double > &offset)
std::map< std::string, std::string > PlannerRunData
Structure to hold information for a single run of a planner.
Maintain a sequence of waypoints and the time durations between these waypoints.
const moveit::core::RobotState & getWayPoint(std::size_t index) const
locale-agnostic conversion functions from floating point numbers to strings
std::string toString(double d)
Convert a double to std::string using the classic C locale.
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
::planning_interface::MotionPlanResponse getShortestSolution(const std::vector<::planning_interface::MotionPlanResponse > &solutions)
Function that returns the shortest solution out of a vector of solutions based on robot_trajectory::p...
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotState >::ConstPtr RobotStateWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::PlanningScene >::ConstPtr PlanningSceneWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::TrajectoryConstraints >::ConstPtr TrajectoryConstraintsWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::PlanningSceneWorld >::ConstPtr PlanningSceneWorldWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::MotionPlanRequest >::ConstPtr MotionPlanRequestWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::Constraints >::ConstPtr ConstraintsWithMetadata
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
std::optional< double > smoothness(const RobotTrajectory &trajectory)
Calculate the smoothness of a given trajectory.
double pathLength(const RobotTrajectory &trajectory)
Calculate the path length of a given trajectory based on the accumulated robot state distances....
Representation of a collision checking request.
Representation of a collision checking result.
bool collision
True if collision was found, false otherwise.
Planner parameters provided with the MotionPlanRequest.
Planner parameters provided with the MotionPlanRequest.
std::vector< moveit_msgs::msg::Constraints > constraints
Options to configure a benchmark experiment. The configuration is provided via ROS2 parameters.
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory