Skip to content

Commit f4cd7d5

Browse files
authored
Enable parallel planning with PipelinePlanner (moveit#450)
* Refactor pipeline planner Make code readable Re-order plan functions Make usable with parallel planning Enable configuring multiple pipelines Add callbacks Cleanup and documentation Add API to set parallel planning callbacks and deprecate functions Pass pipeline map by reference Small clang-tidy fix Update core/src/solvers/pipeline_planner.cpp Co-authored-by: Sebastian Castro <[email protected]> Update core/src/solvers/pipeline_planner.cpp Format Refactor to avoid calling .at(0) twice Use no default stopping criteria Update fallbacks_move demo * Cleanup + address deprecation warnings * Enabling optionally using a property defined pipeline planner map * Address review * Disable humble CI for ros2 branch * Add pipeline planner unittests + some checks * Add short comment
1 parent 0ba9796 commit f4cd7d5

File tree

9 files changed

+340
-169
lines changed

9 files changed

+340
-169
lines changed

.github/workflows/ci.yaml

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,6 @@ jobs:
1919
fail-fast: false
2020
matrix:
2121
env:
22-
- IMAGE: humble-source
2322
- IMAGE: rolling-source
2423
NAME: ccov
2524
TARGET_CMAKE_ARGS: -DCMAKE_BUILD_TYPE=Debug -DCMAKE_CXX_FLAGS="--coverage"

core/include/moveit/task_constructor/solvers/pipeline_planner.h

Lines changed: 117 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -32,13 +32,16 @@
3232
* POSSIBILITY OF SUCH DAMAGE.
3333
*********************************************************************/
3434

35-
/* Authors: Robert Haschke
36-
Desc: plan using MoveIt's PlanningPipeline
35+
/* Authors: Robert Haschke, Sebastian Jahr
36+
Description: Solver that uses a set of MoveIt PlanningPipelines to solve a given planning problem.
3737
*/
3838

3939
#pragma once
4040

4141
#include <moveit/task_constructor/solvers/planner_interface.h>
42+
#include <moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.hpp>
43+
#include <moveit/planning_pipeline_interfaces/solution_selection_functions.hpp>
44+
#include <moveit/planning_pipeline_interfaces/stopping_criterion_functions.hpp>
4245
#include <rclcpp/node.hpp>
4346
#include <moveit/macros/class_forward.h>
4447

@@ -56,48 +59,131 @@ MOVEIT_CLASS_FORWARD(PipelinePlanner);
5659
class PipelinePlanner : public PlannerInterface
5760
{
5861
public:
59-
struct Specification
60-
{
61-
moveit::core::RobotModelConstPtr model;
62-
std::string ns{ "ompl" };
63-
std::string pipeline{ "ompl" };
64-
std::string adapter_param{ "request_adapters" };
65-
};
66-
67-
static planning_pipeline::PlanningPipelinePtr create(const rclcpp::Node::SharedPtr& node,
68-
const moveit::core::RobotModelConstPtr& model) {
69-
Specification spec;
70-
spec.model = model;
71-
return create(node, spec);
62+
/** Simple Constructor to use only a single pipeline
63+
* \param [in] node ROS 2 node
64+
* \param [in] pipeline_name Name of the planning pipeline to be used. This is also the assumed namespace where the
65+
* parameters of this pipeline can be found \param [in] planner_id Planner id to be used for planning
66+
*/
67+
PipelinePlanner(const rclcpp::Node::SharedPtr& node, const std::string& pipeline_name = "ompl",
68+
const std::string& planner_id = "");
69+
70+
[[deprecated("Deprecated: Use new constructor implementations.")]] // clang-format off
71+
PipelinePlanner(const planning_pipeline::PlanningPipelinePtr& /*planning_pipeline*/){};
72+
73+
/** \brief Constructor
74+
* \param [in] node ROS 2 node
75+
* \param [in] pipeline_id_planner_id_map A map containing pairs of planning pipeline name and planner plugin name
76+
* for the planning requests
77+
* \param [in] planning_pipelines Optional: A map with the pipeline names and initialized corresponding planning
78+
* pipelines
79+
* \param [in] stopping_criterion_callback Callback function to stop parallel planning pipeline according to a user defined criteria
80+
* \param [in] solution_selection_function Callback function to choose the best solution when multiple pipelines are used
81+
*/
82+
PipelinePlanner(const rclcpp::Node::SharedPtr& node,
83+
const std::unordered_map<std::string, std::string>& pipeline_id_planner_id_map,
84+
const std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr>& planning_pipelines =
85+
std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr>(),
86+
const moveit::planning_pipeline_interfaces::StoppingCriterionFunction& stopping_criterion_callback = nullptr,
87+
const moveit::planning_pipeline_interfaces::SolutionSelectionFunction& solution_selection_function =
88+
&moveit::planning_pipeline_interfaces::getShortestSolution);
89+
90+
[[deprecated("Replaced with setPlannerId(pipeline_name, planner_id)")]] // clang-format off
91+
void setPlannerId(const std::string& /*planner*/) { /* Do nothing */
7292
}
7393

74-
static planning_pipeline::PlanningPipelinePtr create(const rclcpp::Node::SharedPtr& node, const Specification& spec);
75-
76-
/**
77-
*
78-
* @param node used to load the parameters for the planning pipeline
94+
/** \brief Set the planner id for a specific planning pipeline for the planning requests
95+
* \param [in] pipeline_name Name of the planning pipeline for which the planner id is set
96+
* \param [in] planner_id Name of the planner ID that should be used by the planning pipeline
97+
* \return true if the pipeline exists and the corresponding ID is set successfully
98+
*/
99+
bool setPlannerId(const std::string& pipeline_name, const std::string& planner_id);
100+
101+
/** \brief Set stopping criterion function for parallel planning
102+
* \param [in] stopping_criterion_callback New stopping criterion function that will be used
103+
*/
104+
void setStoppingCriterionFunction(const moveit::planning_pipeline_interfaces::StoppingCriterionFunction& stopping_criterion_callback);
105+
106+
/** \brief Set solution selection function for parallel planning
107+
* \param [in] solution_selection_function New solution selection that will be used
108+
*/
109+
void setSolutionSelectionFunction(const moveit::planning_pipeline_interfaces::SolutionSelectionFunction& solution_selection_function);
110+
111+
/** \brief This function is called when an MTC task that uses this solver is initialized. If no pipelines are
112+
* configured when this function is invoked, the planning pipelines named in the 'pipeline_id_planner_id_map' are
113+
* initialized with the given robot model.
114+
* \param [in] robot_model A robot model that is used to initialize the
115+
* planning pipelines of this solver
79116
*/
80-
PipelinePlanner(const rclcpp::Node::SharedPtr& node, const std::string& pipeline = "ompl");
81-
82-
PipelinePlanner(const planning_pipeline::PlanningPipelinePtr& planning_pipeline);
83-
84-
void setPlannerId(const std::string& planner) { setProperty("planner", planner); }
85-
86117
void init(const moveit::core::RobotModelConstPtr& robot_model) override;
87118

119+
/**
120+
* \brief Plan a trajectory from a planning scene 'from' to scene 'to'
121+
* \param [in] from Start planning scene
122+
* \param [in] to Goal planning scene (used to create goal constraints)
123+
* \param [in] joint_model_group Group of joints for which this trajectory is created
124+
* \param [in] timeout Maximum planning timeout for an individual stage that is using the pipeline planner in seconds
125+
* \param [in] result Reference to the location where the created trajectory is stored if planning is successful
126+
* \param [in] path_constraints Path contraints for the planning problem
127+
* \return true If the solver found a successful solution for the given planning problem
128+
*/
88129
bool plan(const planning_scene::PlanningSceneConstPtr& from, const planning_scene::PlanningSceneConstPtr& to,
89-
const core::JointModelGroup* jmg, double timeout, robot_trajectory::RobotTrajectoryPtr& result,
130+
const core::JointModelGroup* joint_model_group, double timeout,
131+
robot_trajectory::RobotTrajectoryPtr& result,
90132
const moveit_msgs::msg::Constraints& path_constraints = moveit_msgs::msg::Constraints()) override;
91133

134+
/** \brief Plan a trajectory from a planning scene 'from' to a target pose with an offset
135+
* \param [in] from Start planning scene
136+
* \param [in] link Link for which a target pose is given
137+
* \param [in] offset Offset to be applied to a given target pose
138+
* \param [in] target Target pose
139+
* \param [in] joint_model_group Group of joints for which this trajectory is created
140+
* \param [in] timeout Maximum planning timeout for an individual stage that is using the pipeline planner in seconds
141+
* \param [in] result Reference to the location where the created trajectory is stored if planning is successful
142+
* \param [in] path_constraints Path contraints for the planning problem
143+
* \return true If the solver found a successful solution for the given planning problem
144+
*/
92145
bool plan(const planning_scene::PlanningSceneConstPtr& from, const moveit::core::LinkModel& link,
93-
const Eigen::Isometry3d& offset, const Eigen::Isometry3d& target, const moveit::core::JointModelGroup* jmg,
94-
double timeout, robot_trajectory::RobotTrajectoryPtr& result,
146+
const Eigen::Isometry3d& offset, const Eigen::Isometry3d& target,
147+
const moveit::core::JointModelGroup* joint_model_group, double timeout,
148+
robot_trajectory::RobotTrajectoryPtr& result,
95149
const moveit_msgs::msg::Constraints& path_constraints = moveit_msgs::msg::Constraints()) override;
96150

97151
protected:
98-
std::string pipeline_name_;
99-
planning_pipeline::PlanningPipelinePtr planner_;
152+
/** \brief Function that actually uses the planning pipelines to solve the given planning problem. It is called by
153+
* the public plan function after the goal constraints are generated. This function uses a predefined number of
154+
* planning pipelines in parallel to solve the planning problem and choose the best (user-defined) solution.
155+
* \param [in] planning_scene Scene for which the planning should be solved
156+
* \param [in] joint_model_group
157+
* Group of joints for which this trajectory is created
158+
* \param [in] goal_constraints Set of constraints that need to
159+
* be satisfied by the solution
160+
* \param [in] timeout Maximum planning timeout for an individual stage that is using the pipeline planner in seconds
161+
* \param [in] result Reference to the location where the created
162+
* trajectory is stored if planning is successful
163+
* \param [in] path_constraints Path contraints for the planning
164+
* problem
165+
* \return true If the solver found a successful solution for the given planning problem
166+
*/
167+
bool plan(const planning_scene::PlanningSceneConstPtr& planning_scene,
168+
const moveit::core::JointModelGroup* joint_model_group,
169+
const moveit_msgs::msg::Constraints& goal_constraints, double timeout,
170+
robot_trajectory::RobotTrajectoryPtr& result,
171+
const moveit_msgs::msg::Constraints& path_constraints = moveit_msgs::msg::Constraints());
172+
100173
rclcpp::Node::SharedPtr node_;
174+
175+
/** \brief Map of pipeline names (ids) and their corresponding planner ids. The planning problem is solved for every
176+
* pipeline-planner pair in this map. If no pipelines are passed via constructor argument, the pipeline names are
177+
* used to initialize a set of planning pipelines. */
178+
std::unordered_map<std::string, std::string> pipeline_id_planner_id_map_;
179+
180+
/** \brief Map of pipelines names and planning pipelines. This map is used to quickly search for a requested motion
181+
* planning pipeline when during plan(..) */
182+
std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr> planning_pipelines_;
183+
184+
moveit::planning_pipeline_interfaces::StoppingCriterionFunction stopping_criterion_callback_;
185+
moveit::planning_pipeline_interfaces::SolutionSelectionFunction solution_selection_function_;
186+
101187
};
102188
} // namespace solvers
103189
} // namespace task_constructor

0 commit comments

Comments
 (0)