Skip to content

Commit abbbb9d

Browse files
sjahrAndyZe
andauthored
Parallel planning pipelines (moveit#1420)
* Add setTrajectoryConstraints() to PlanningComponent * Add planning time to PlanningComponent::PlanSolution * Replace PlanSolution with MotionPlanResponse * Address review * Add MultiPipelinePlanRequestParameters Add plan(const MultiPipelinePlanRequestParameters& parameters) Add mutex to avoid segfaults Add optional stop_criterion_callback and solution_selection_callback Remove stop_criterion_callback Make default solution_selection_callback = nullptr Remove parameter handling copy&paste code in favor of a template Add TODO to refactor pushBack() method into insert() Fix selection criteria and add RCLCPP_INFO output Changes due to rebase and formatting Fix race condition and segfault when no solution is found Satisfy clang tidy Remove mutex and thread safety TODOs Add stopping functionality to parallel planning Remove unnecessary TODOs * Fix unused plan solution with failure * Add sanity check for number of parallel planning problems * Check stopping criterion when new solution is generated + make thread safe * Add terminatePlanningPipeline() to MoveItCpp interface * Format! * Bug fixes * Move getShortestSolution callback into own function * No east const * Remove PlanSolutions and make planner_id accessible * Make solution executable * Rename update_last_solution to store_solution * Alphabetize includes and include plan_solutions.hpp instead of .h * Address review * Add missing header * Apply suggestions from code review Co-authored-by: AndyZe <[email protected]> Co-authored-by: AndyZe <[email protected]>
1 parent afef073 commit abbbb9d

File tree

9 files changed

+385
-70
lines changed

9 files changed

+385
-70
lines changed

moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h

+19-2
Original file line numberDiff line numberDiff line change
@@ -37,23 +37,39 @@
3737
#pragma once
3838

3939
#include <moveit/robot_trajectory/robot_trajectory.h>
40+
#include <moveit/utils/moveit_error_code.h>
4041
#include <moveit_msgs/msg/move_it_error_codes.hpp>
4142
#include <moveit_msgs/msg/motion_plan_response.hpp>
4243
#include <moveit_msgs/msg/motion_plan_detailed_response.hpp>
4344

4445
namespace planning_interface
4546
{
47+
/// \brief Response to a planning query
4648
struct MotionPlanResponse
4749
{
48-
MotionPlanResponse() : planning_time_(0.0)
50+
/** \brief Constructor */
51+
MotionPlanResponse() : trajectory_(nullptr), planning_time_(0.0), error_code_(moveit::core::MoveItErrorCode::FAILURE)
4952
{
5053
}
5154

55+
/** \brief Construct a ROS message from struct data */
5256
void getMessage(moveit_msgs::msg::MotionPlanResponse& msg) const;
5357

58+
// Trajectory generated by the queried planner
5459
robot_trajectory::RobotTrajectoryPtr trajectory_;
60+
// Time to plan the respond to the planning query
5561
double planning_time_;
56-
moveit_msgs::msg::MoveItErrorCodes error_code_;
62+
// Result status of the query
63+
moveit::core::MoveItErrorCode error_code_;
64+
/// The full starting state used for planning
65+
moveit_msgs::msg::RobotState start_state_;
66+
std::string planner_id_;
67+
68+
// \brief Enable checking of query success or failure, for example if(response) ...
69+
explicit operator bool() const
70+
{
71+
return bool(error_code_);
72+
}
5773
};
5874

5975
struct MotionPlanDetailedResponse
@@ -64,6 +80,7 @@ struct MotionPlanDetailedResponse
6480
std::vector<std::string> description_;
6581
std::vector<double> processing_time_;
6682
moveit_msgs::msg::MoveItErrorCodes error_code_;
83+
std::string planner_id_;
6784
};
6885

6986
} // namespace planning_interface

moveit_ros/hybrid_planning/global_planner/global_planner_plugins/src/moveit_planning_pipeline.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -132,17 +132,17 @@ moveit_msgs::msg::MotionPlanResponse MoveItPlanningPipeline::plan(
132132

133133
// Plan motion
134134
auto plan_solution = planning_components->plan(plan_params);
135-
if (plan_solution.error_code != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
135+
if (!bool(plan_solution.error_code_))
136136
{
137-
response.error_code = plan_solution.error_code;
137+
response.error_code = plan_solution.error_code_;
138138
return response;
139139
}
140140

141141
// Transform solution into MotionPlanResponse and publish it
142-
response.trajectory_start = plan_solution.start_state;
142+
response.trajectory_start = plan_solution.start_state_;
143143
response.group_name = motion_plan_req.group_name;
144-
plan_solution.trajectory->getRobotTrajectoryMsg(response.trajectory);
145-
response.error_code = plan_solution.error_code;
144+
plan_solution.trajectory_->getRobotTrajectoryMsg(response.trajectory);
145+
response.error_code = plan_solution.error_code_;
146146

147147
return response;
148148
}

moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h

+3
Original file line numberDiff line numberDiff line change
@@ -172,6 +172,9 @@ class MoveItCpp
172172
const robot_trajectory::RobotTrajectoryPtr& robot_trajectory,
173173
bool blocking = true);
174174

175+
/** \brief Utility to terminate all active planning pipelines */
176+
bool terminatePlanningPipeline(const std::string& pipeline_name);
177+
175178
private:
176179
// Core properties and instances
177180
rclcpp::Node::SharedPtr node_;
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,105 @@
1+
/*********************************************************************
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2019, 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+
Desc: A safe data structure for MotionPlanResponses and free functions to analyze them */
37+
38+
#pragma once
39+
40+
#include <algorithm>
41+
#include <moveit/planning_interface/planning_response.h>
42+
#include <thread>
43+
44+
namespace moveit_cpp
45+
{
46+
MOVEIT_CLASS_FORWARD(PlanSolutions); // Defines PlanningComponentPtr, ConstPtr, WeakPtr... etc
47+
48+
/** \brief A container to thread-safely store multiple MotionPlanResponses for later usage */
49+
class PlanSolutions
50+
{
51+
public:
52+
PlanSolutions(const size_t expected_size = 0)
53+
{
54+
solutions_.reserve(expected_size);
55+
}
56+
57+
/** \brief Thread safe method to add PlanSolutions to this data structure TODO(sjahr): Refactor this method to an
58+
* insert method similar to https://github.com/ompl/ompl/blob/main/src/ompl/base/src/ProblemDefinition.cpp#L54-L161.
59+
* This way, it is possible to created a sorted container e.g. according to a user specified criteria
60+
*/
61+
void pushBack(planning_interface::MotionPlanResponse plan_solution)
62+
{
63+
std::lock_guard<std::mutex> lock_guard(solutions_mutex_);
64+
solutions_.push_back(plan_solution);
65+
}
66+
67+
/** \brief Get solutions */
68+
const std::vector<planning_interface::MotionPlanResponse>& getSolutions() const
69+
{
70+
return solutions_;
71+
}
72+
73+
private:
74+
std::vector<planning_interface::MotionPlanResponse> solutions_;
75+
std::mutex solutions_mutex_;
76+
};
77+
78+
/** \brief Function that returns the shortest solution out of a vector of solutions based on robot_trajectory::path_length(...)
79+
* \param [in] solutions Vector of solutions to chose the shortest one from
80+
* \return Shortest solution, trajectory_ of the returned MotionPlanResponse is a nullptr if no solution is found!
81+
*/
82+
planning_interface::MotionPlanResponse
83+
getShortestSolution(const std::vector<planning_interface::MotionPlanResponse>& solutions)
84+
{
85+
// Find trajectory with minimal path
86+
auto const shortest_trajectory = std::min_element(solutions.begin(), solutions.end(),
87+
[](const planning_interface::MotionPlanResponse& solution_a,
88+
const planning_interface::MotionPlanResponse& solution_b) {
89+
// If both solutions were successful, check which path is shorter
90+
if (solution_a && solution_b)
91+
{
92+
return robot_trajectory::path_length(*solution_a.trajectory_) <
93+
robot_trajectory::path_length(*solution_b.trajectory_);
94+
}
95+
// If only solution a is successful, return a
96+
else if (solution_a)
97+
{
98+
return true;
99+
}
100+
// Else return solution b, either because it is successful or not
101+
return false;
102+
});
103+
return *shortest_trajectory;
104+
}
105+
} // namespace moveit_cpp

moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h

+76-36
Original file line numberDiff line numberDiff line change
@@ -37,42 +37,22 @@
3737

3838
#pragma once
3939

40-
#include <rclcpp/rclcpp.hpp>
41-
#include <moveit/moveit_cpp/moveit_cpp.h>
42-
#include <moveit/robot_state/robot_state.h>
4340
#include <geometry_msgs/msg/pose_stamped.h>
41+
#include <moveit/moveit_cpp/moveit_cpp.h>
42+
#include <moveit/moveit_cpp/plan_solutions.hpp>
43+
#include <moveit/planning_interface/planning_response.h>
4444
#include <moveit/robot_state/conversions.h>
45+
#include <moveit/robot_state/robot_state.h>
4546
#include <moveit/utils/moveit_error_code.h>
47+
#include <rclcpp/rclcpp.hpp>
4648

4749
namespace moveit_cpp
4850
{
4951
MOVEIT_CLASS_FORWARD(PlanningComponent); // Defines PlanningComponentPtr, ConstPtr, WeakPtr... etc
50-
5152
class PlanningComponent
5253
{
5354
public:
54-
MOVEIT_STRUCT_FORWARD(PlanSolution);
55-
5655
using MoveItErrorCode [[deprecated("Use moveit::core::MoveItErrorCode")]] = moveit::core::MoveItErrorCode;
57-
58-
/// The representation of a plan solution
59-
struct PlanSolution
60-
{
61-
/// The full starting state used for planning
62-
moveit_msgs::msg::RobotState start_state;
63-
64-
/// The trajectory of the robot (may not contain joints that are the same as for the start_state_)
65-
robot_trajectory::RobotTrajectoryPtr trajectory;
66-
67-
/// Reason why the plan failed
68-
moveit::core::MoveItErrorCode error_code;
69-
70-
explicit operator bool() const
71-
{
72-
return bool(error_code);
73-
}
74-
};
75-
7656
/// Planner parameters provided with the MotionPlanRequest
7757
struct PlanRequestParameters
7858
{
@@ -83,18 +63,67 @@ class PlanningComponent
8363
double max_velocity_scaling_factor;
8464
double max_acceleration_scaling_factor;
8565

86-
void load(const rclcpp::Node::SharedPtr& node)
66+
template <typename T>
67+
void declareOrGetParam(const rclcpp::Node::SharedPtr& node, const std::string& param_name, T& output_value,
68+
T default_value)
69+
{
70+
// Try to get parameter or use default
71+
if (!node->get_parameter_or(param_name, output_value, default_value))
72+
{
73+
RCLCPP_WARN(node->get_logger(),
74+
"Parameter \'%s\' not found in config use default value instead, check parameter type and "
75+
"namespace in YAML file",
76+
(param_name).c_str());
77+
}
78+
}
79+
80+
void load(const rclcpp::Node::SharedPtr& node, const std::string& param_namespace = "")
8781
{
82+
// Set namespace
8883
std::string ns = "plan_request_params.";
89-
node->get_parameter_or(ns + "planner_id", planner_id, std::string(""));
90-
node->get_parameter_or(ns + "planning_pipeline", planning_pipeline, std::string(""));
91-
node->get_parameter_or(ns + "planning_time", planning_time, 1.0);
92-
node->get_parameter_or(ns + "planning_attempts", planning_attempts, 5);
93-
node->get_parameter_or(ns + "max_velocity_scaling_factor", max_velocity_scaling_factor, 1.0);
94-
node->get_parameter_or(ns + "max_acceleration_scaling_factor", max_acceleration_scaling_factor, 1.0);
84+
if (!param_namespace.empty())
85+
{
86+
ns = param_namespace + ".plan_request_params.";
87+
}
88+
89+
// Declare parameters
90+
declareOrGetParam<std::string>(node, ns + "planner_id", planner_id, std::string(""));
91+
declareOrGetParam<std::string>(node, ns + "planning_pipeline", planning_pipeline, std::string(""));
92+
declareOrGetParam<double>(node, ns + "planning_time", planning_time, 1.0);
93+
declareOrGetParam<int>(node, ns + "planning_attempts", planning_attempts, 5);
94+
declareOrGetParam<double>(node, ns + "max_velocity_scaling_factor", max_velocity_scaling_factor, 1.0);
95+
declareOrGetParam<double>(node, ns + "max_acceleration_scaling_factor", max_acceleration_scaling_factor, 1.0);
9596
}
9697
};
9798

99+
/// Planner parameters provided with the MotionPlanRequest
100+
struct MultiPipelinePlanRequestParameters
101+
{
102+
MultiPipelinePlanRequestParameters(const rclcpp::Node::SharedPtr& node,
103+
const std::vector<std::string>& planning_pipeline_names)
104+
{
105+
multi_plan_request_parameters.reserve(planning_pipeline_names.size());
106+
107+
for (const auto& planning_pipeline_name : planning_pipeline_names)
108+
{
109+
PlanRequestParameters parameters;
110+
parameters.load(node, planning_pipeline_name);
111+
multi_plan_request_parameters.push_back(parameters);
112+
}
113+
}
114+
// Plan request parameters for the individual planning pipelines which run concurrently
115+
std::vector<PlanRequestParameters> multi_plan_request_parameters;
116+
};
117+
118+
/** \brief A solution callback function type for the parallel planning API of planning component */
119+
typedef std::function<planning_interface::MotionPlanResponse(
120+
const std::vector<planning_interface::MotionPlanResponse>& solutions)>
121+
SolutionCallbackFunction;
122+
/** \brief A stopping criterion callback function for the parallel planning API of planning component */
123+
typedef std::function<bool(const PlanSolutions& solutions,
124+
const MultiPipelinePlanRequestParameters& plan_request_parameters)>
125+
StoppingCriterionFunction;
126+
98127
/** \brief Constructor */
99128
PlanningComponent(const std::string& group_name, const rclcpp::Node::SharedPtr& node);
100129
PlanningComponent(const std::string& group_name, const MoveItCppPtr& moveit_cpp);
@@ -154,19 +183,29 @@ class PlanningComponent
154183
/** \brief Set the path constraints generated from a moveit msg Constraints */
155184
bool setPathConstraints(const moveit_msgs::msg::Constraints& path_constraints);
156185

186+
/** \brief Set the trajectory constraints generated from a moveit msg Constraints */
187+
bool setTrajectoryConstraints(const moveit_msgs::msg::TrajectoryConstraints& trajectory_constraints);
188+
157189
/** \brief Run a plan from start or current state to fulfill the last goal constraints provided by setGoal() using
158190
* default parameters. */
159-
PlanSolution plan();
191+
planning_interface::MotionPlanResponse plan();
192+
/** \brief Run a plan from start or current state to fulfill the last goal constraints provided by setGoal() using the
193+
* provided PlanRequestParameters. */
194+
planning_interface::MotionPlanResponse plan(const PlanRequestParameters& parameters, const bool store_solution = true);
195+
160196
/** \brief Run a plan from start or current state to fulfill the last goal constraints provided by setGoal() using the
161197
* provided PlanRequestParameters. */
162-
PlanSolution plan(const PlanRequestParameters& parameters);
198+
planning_interface::MotionPlanResponse
199+
plan(const MultiPipelinePlanRequestParameters& parameters,
200+
SolutionCallbackFunction solution_selection_callback = &getShortestSolution,
201+
StoppingCriterionFunction stopping_criterion_callback = nullptr);
163202

164203
/** \brief Execute the latest computed solution trajectory computed by plan(). By default this function terminates
165204
* after the execution is complete. The execution can be run in background by setting blocking to false. */
166205
bool execute(bool blocking = true);
167206

168207
/** \brief Return the last plan solution*/
169-
const PlanSolutionPtr getLastPlanSolution();
208+
const planning_interface::MotionPlanResponse& getLastMotionPlanResponse();
170209

171210
private:
172211
// Core properties and instances
@@ -182,10 +221,11 @@ class PlanningComponent
182221
moveit::core::RobotStatePtr considered_start_state_;
183222
std::vector<moveit_msgs::msg::Constraints> current_goal_constraints_;
184223
moveit_msgs::msg::Constraints current_path_constraints_;
224+
moveit_msgs::msg::TrajectoryConstraints current_trajectory_constraints_;
185225
PlanRequestParameters plan_request_parameters_;
186226
moveit_msgs::msg::WorkspaceParameters workspace_parameters_;
187227
bool workspace_parameters_set_ = false;
188-
PlanSolutionPtr last_plan_solution_;
228+
planning_interface::MotionPlanResponse last_plan_solution_;
189229

190230
// common properties for goals
191231
// TODO(henningkayser): support goal tolerances

moveit_ros/planning/moveit_cpp/src/moveit_cpp.cpp

+19
Original file line numberDiff line numberDiff line change
@@ -276,6 +276,25 @@ MoveItCpp::execute(const std::string& group_name, const robot_trajectory::RobotT
276276
return moveit_controller_manager::ExecutionStatus::RUNNING;
277277
}
278278

279+
bool MoveItCpp::terminatePlanningPipeline(const std::string& pipeline_name)
280+
{
281+
try
282+
{
283+
const auto& planning_pipeline = planning_pipelines_.at(pipeline_name);
284+
if (planning_pipeline->isActive())
285+
{
286+
planning_pipeline->terminate();
287+
}
288+
return true;
289+
}
290+
catch (const std::out_of_range& oor)
291+
{
292+
RCLCPP_ERROR(LOGGER, "Cannot terminate pipeline '%s' because no pipeline with that name exists",
293+
pipeline_name.c_str());
294+
return false;
295+
}
296+
}
297+
279298
const std::shared_ptr<tf2_ros::Buffer>& MoveItCpp::getTFBuffer() const
280299
{
281300
return planning_scene_monitor_->getTFClient();

0 commit comments

Comments
 (0)