moveit2
The MoveIt Motion Planning Framework for ROS 2.
planning_pipeline_interfaces.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2023, PickNik Inc.
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 PickNik Inc. 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: Sebastian Jahr */
36 
38 #include <moveit/utils/logger.hpp>
39 
40 #include <thread>
41 
42 namespace moveit
43 {
44 namespace planning_pipeline_interfaces
45 {
46 
47 rclcpp::Logger getLogger()
48 {
49  return moveit::getLogger("moveit.ros.planning_pipeline_interfaces");
50 }
51 
54  const ::planning_scene::PlanningSceneConstPtr& planning_scene,
55  const std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr>& planning_pipelines)
56 {
57  ::planning_interface::MotionPlanResponse motion_plan_response;
58  auto it = planning_pipelines.find(motion_plan_request.pipeline_id);
59  if (it == planning_pipelines.end())
60  {
61  RCLCPP_ERROR(getLogger(), "No planning pipeline available for name '%s'", motion_plan_request.pipeline_id.c_str());
62  motion_plan_response.error_code = moveit::core::MoveItErrorCode::FAILURE;
63  return motion_plan_response;
64  }
65  const planning_pipeline::PlanningPipelinePtr pipeline = it->second;
66  if (!pipeline->generatePlan(planning_scene, motion_plan_request, motion_plan_response))
67  {
68  if ((motion_plan_response.error_code.val == moveit::core::MoveItErrorCode::SUCCESS) ||
69  (motion_plan_response.error_code.val == moveit::core::MoveItErrorCode::UNDEFINED))
70  {
71  RCLCPP_ERROR(getLogger(), "Planning pipeline '%s' failed to plan, but did not set an error code",
72  motion_plan_request.pipeline_id.c_str());
73  motion_plan_response.error_code = moveit::core::MoveItErrorCode::FAILURE;
74  }
75  }
76  return motion_plan_response;
77 }
78 
79 const std::vector<::planning_interface::MotionPlanResponse> planWithParallelPipelines(
80  const std::vector<::planning_interface::MotionPlanRequest>& motion_plan_requests,
81  const ::planning_scene::PlanningSceneConstPtr& planning_scene,
82  const std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr>& planning_pipelines,
83  const StoppingCriterionFunction& stopping_criterion_callback,
84  const SolutionSelectionFunction& solution_selection_function)
85 {
86  // Create solutions container
87  PlanResponsesContainer plan_responses_container{ motion_plan_requests.size() };
88  std::vector<std::thread> planning_threads;
89  planning_threads.reserve(motion_plan_requests.size());
90 
91  // Print a warning if more parallel planning problems than available concurrent threads are defined. If
92  // std::thread::hardware_concurrency() is not defined, the command returns 0 so the check does not work
93  const auto hardware_concurrency = std::thread::hardware_concurrency();
94  if (motion_plan_requests.size() > hardware_concurrency && hardware_concurrency != 0)
95  {
96  RCLCPP_WARN(getLogger(),
97  "More parallel planning problems defined ('%ld') than possible to solve concurrently with the "
98  "hardware ('%d')",
99  motion_plan_requests.size(), hardware_concurrency);
100  }
101 
102  // Launch planning threads
103  for (const auto& request : motion_plan_requests)
104  {
105  auto planning_thread = std::thread([&]() {
106  auto plan_solution = ::planning_interface::MotionPlanResponse();
107  try
108  {
109  // Use planning scene if provided, otherwise the planning scene from planning scene monitor is used
110  plan_solution = planWithSinglePipeline(request, planning_scene, planning_pipelines);
111  }
112  catch (const std::exception& e)
113  {
114  RCLCPP_ERROR(getLogger(), "Planning pipeline '%s' threw exception '%s'", request.pipeline_id.c_str(), e.what());
116  plan_solution.error_code = moveit::core::MoveItErrorCode::FAILURE;
117  }
118  plan_solution.planner_id = request.planner_id;
119  plan_responses_container.pushBack(plan_solution);
120 
121  if (stopping_criterion_callback != nullptr)
122  {
123  if (stopping_criterion_callback(plan_responses_container, motion_plan_requests))
124  {
125  // Terminate planning pipelines
126  RCLCPP_INFO(getLogger(), "Stopping criterion met: Terminating planning pipelines that are still active");
127  for (const auto& request : motion_plan_requests)
128  {
129  try
130  {
131  const auto& planning_pipeline = planning_pipelines.at(request.pipeline_id);
132  if (planning_pipeline->isActive())
133  {
134  planning_pipeline->terminate();
135  }
136  }
137  catch (const std::out_of_range&)
138  {
139  RCLCPP_WARN(getLogger(), "Cannot terminate pipeline '%s' because no pipeline with that name exists",
140  request.pipeline_id.c_str());
141  }
142  }
143  }
144  }
145  });
146  planning_threads.push_back(std::move(planning_thread));
147  }
148 
149  // Wait for threads to finish
150  for (auto& planning_thread : planning_threads)
151  {
152  if (planning_thread.joinable())
153  {
154  planning_thread.join();
155  }
156  }
157 
158  // If a solution selection function is provided, it is used to compute the return value
159  if (solution_selection_function)
160  {
161  std::vector<::planning_interface::MotionPlanResponse> solutions;
162  solutions.reserve(1);
163  solutions.push_back(solution_selection_function(plan_responses_container.getSolutions()));
164  return solutions;
165  }
166 
167  // Otherwise, just return the unordered list of solutions
168  return plan_responses_container.getSolutions();
169 }
170 
171 std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr>
172 createPlanningPipelineMap(const std::vector<std::string>& pipeline_names,
173  const moveit::core::RobotModelConstPtr& robot_model, const rclcpp::Node::SharedPtr& node,
174  const std::string& parameter_namespace)
175 {
176  std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr> planning_pipelines;
177  for (const auto& planning_pipeline_name : pipeline_names)
178  {
179  // Check if pipeline already exists
180  if (planning_pipelines.count(planning_pipeline_name) > 0)
181  {
182  RCLCPP_WARN(getLogger(), "Skipping duplicate entry for planning pipeline '%s'.", planning_pipeline_name.c_str());
183  continue;
184  }
185 
186  // Create planning pipeline
187  planning_pipeline::PlanningPipelinePtr pipeline = std::make_shared<planning_pipeline::PlanningPipeline>(
188  robot_model, node, parameter_namespace + planning_pipeline_name);
189 
190  if (!pipeline)
191  {
192  RCLCPP_ERROR(getLogger(), "Failed to initialize planning pipeline '%s'.", planning_pipeline_name.c_str());
193  continue;
194  }
195 
196  planning_pipelines[planning_pipeline_name] = pipeline;
197  }
198 
199  return planning_pipelines;
200 }
201 
202 } // namespace planning_pipeline_interfaces
203 } // namespace moveit
A container to thread-safely store multiple MotionPlanResponses.
::planning_interface::MotionPlanResponse planWithSinglePipeline(const ::planning_interface::MotionPlanRequest &motion_plan_request, const ::planning_scene::PlanningSceneConstPtr &planning_scene, const std::unordered_map< std::string, planning_pipeline::PlanningPipelinePtr > &planning_pipelines)
Function to calculate the MotionPlanResponse for a given MotionPlanRequest and a PlanningScene.
std::unordered_map< std::string, planning_pipeline::PlanningPipelinePtr > createPlanningPipelineMap(const std::vector< std::string > &pipeline_names, const moveit::core::RobotModelConstPtr &robot_model, const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace=std::string())
Utility function to create a map of named planning pipelines.
std::function< bool(const PlanResponsesContainer &plan_responses_container, const std::vector<::planning_interface::MotionPlanRequest > &plan_requests)> StoppingCriterionFunction
A stopping criterion callback function for the parallel planning API of planning component.
const std::vector<::planning_interface::MotionPlanResponse > planWithParallelPipelines(const std::vector<::planning_interface::MotionPlanRequest > &motion_plan_requests, const ::planning_scene::PlanningSceneConstPtr &planning_scene, const std::unordered_map< std::string, planning_pipeline::PlanningPipelinePtr > &planning_pipelines, const StoppingCriterionFunction &stopping_criterion_callback=nullptr, const SolutionSelectionFunction &solution_selection_function=nullptr)
Function to solve multiple planning problems in parallel threads with multiple planning pipelines at ...
std::function<::planning_interface::MotionPlanResponse(const std::vector<::planning_interface::MotionPlanResponse > &solutions)> SolutionSelectionFunction
A solution callback function type for the parallel planning API of planning component.
Main namespace for MoveIt.
Definition: exceptions.hpp:43
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
moveit::core::MoveItErrorCode error_code