@@ -61,30 +61,36 @@ class PipelinePlanner : public PlannerInterface
6161public:
6262 /* * Simple Constructor to use only a single pipeline
6363 * \param [in] node ROS 2 node
64- * \param [in] pipeline_name Name of the planning pipeline to be used.
65- * This is also the assumed namespace where the parameters of this pipeline can be found
66- * \param [in] planner_id Planner id to be used for planning. Empty string means default.
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
6766 */
6867 PipelinePlanner (const rclcpp::Node::SharedPtr& node, const std::string& pipeline_name = " ompl" ,
6968 const std::string& planner_id = " " )
7069 : PipelinePlanner(node, { { pipeline_name, planner_id } }) {}
7170
7271 /* * \brief Constructor
7372 * \param [in] node ROS 2 node
74- * \param [in] pipeline_id_planner_id_map map containing pairs of pipeline and plugin names to be used for planning
75- * \param [in] stopping_criterion_callback callback to decide when to stop parallel planning
76- * \param [in] solution_selection_function callback to choose the best solution from multiple ran pipelines
73+ * \param [in] pipeline_id_planner_id_map A map containing pairs of planning pipeline name and planner plugin name
74+ * for the planning requests
75+ * \param [in] planning_pipelines Optional: A map with the pipeline names and initialized corresponding planning
76+ * pipelines
77+ * \param [in] stopping_criterion_callback Callback function to stop parallel planning pipeline according to a user
78+ * defined criteria
79+ * \param [in] solution_selection_function Callback function to choose the best solution when
80+ * multiple pipelines are used
7781 */
7882 PipelinePlanner (
7983 const rclcpp::Node::SharedPtr& node,
8084 const std::unordered_map<std::string, std::string>& pipeline_id_planner_id_map,
85+ const std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr>& planning_pipelines =
86+ std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr>(),
8187 const moveit::planning_pipeline_interfaces::StoppingCriterionFunction& stopping_criterion_callback = nullptr ,
8288 const moveit::planning_pipeline_interfaces::SolutionSelectionFunction& solution_selection_function =
8389 &moveit::planning_pipeline_interfaces::getShortestSolution);
8490
85- /* * \brief Set the planner id for a specific planning pipeline
86- * \param [in] pipeline_name Name of the to-be-used planning pipeline
87- * \param [in] planner_id Name of the to-be- used planner ID
91+ /* * \brief Set the planner id for a specific planning pipeline for the planning requests
92+ * \param [in] pipeline_name Name of the planning pipeline for which the planner id is set
93+ * \param [in] planner_id Name of the planner ID that should be used by the planning pipeline
8894 * \return true if the pipeline exists and the corresponding ID is set successfully
8995 */
9096 bool setPlannerId (const std::string& pipeline_name, const std::string& planner_id);
@@ -101,26 +107,31 @@ class PipelinePlanner : public PlannerInterface
101107 void setSolutionSelectionFunction (
102108 const moveit::planning_pipeline_interfaces::SolutionSelectionFunction& solution_selection_function);
103109
104- /* * \brief If not yet done, initialize pipelines from pipeline_id_planner_id_map
105- * \param [in] robot_model robot model used to initialize the planning pipelines of this solver
110+ /* * \brief This function is called when an MTC task that uses this solver is initialized. If no pipelines are
111+ * configured when this function is invoked, the planning pipelines named in the 'pipeline_id_planner_id_map' are
112+ * initialized with the given robot model.
113+ * \param [in] robot_model A robot model that is used to initialize the
114+ * planning pipelines of this solver
106115 */
107116 void init (const moveit::core::RobotModelConstPtr& robot_model) override ;
108117
109- /* * \brief Plan a trajectory from a planning scene 'from' to scene 'to'
118+ /* *
119+ * \brief Plan a trajectory from a planning scene 'from' to scene 'to'
110120 * \param [in] from Start planning scene
111121 * \param [in] to Goal planning scene (used to create goal constraints)
112122 * \param [in] joint_model_group Group of joints for which this trajectory is created
113123 * \param [in] timeout Maximum planning timeout for an individual stage that is using the pipeline planner in seconds
114124 * \param [in] result Reference to the location where the created trajectory is stored if planning is successful
115125 * \param [in] path_constraints Path contraints for the planning problem
116- * \return true If the solver found a successful solution for the given planning problem
126+ * \return MoveItErrorCode - Return MoveItErrorCodes::SUCCESS if solver found a successful solution. Otherwise,
127+ * return an appropriate error type and message explaining why it failed.
117128 */
118- Result plan ( const planning_scene::PlanningSceneConstPtr& from, const planning_scene::PlanningSceneConstPtr& to,
119- const core::JointModelGroup* joint_model_group, double timeout ,
120- robot_trajectory::RobotTrajectoryPtr& result,
121- const moveit_msgs::msg::Constraints& path_constraints = moveit_msgs::msg::Constraints()) override ;
129+ MoveItErrorCode
130+ plan ( const planning_scene::PlanningSceneConstPtr& from, const planning_scene::PlanningSceneConstPtr& to ,
131+ const core::JointModelGroup* joint_model_group, double timeout, robot_trajectory::RobotTrajectoryPtr& result,
132+ const moveit_msgs::msg::Constraints& path_constraints = moveit_msgs::msg::Constraints()) override ;
122133
123- /* * \brief Plan a trajectory from a planning scene 'from' to a Cartesian target pose with an offset
134+ /* * \brief Plan a trajectory from a planning scene 'from' to a target pose with an offset
124135 * \param [in] from Start planning scene
125136 * \param [in] link Link for which a target pose is given
126137 * \param [in] offset Offset to be applied to a given target pose
@@ -129,37 +140,55 @@ class PipelinePlanner : public PlannerInterface
129140 * \param [in] timeout Maximum planning timeout for an individual stage that is using the pipeline planner in seconds
130141 * \param [in] result Reference to the location where the created trajectory is stored if planning is successful
131142 * \param [in] path_constraints Path contraints for the planning problem
132- * \return true If the solver found a successful solution for the given planning problem
143+ * \return MoveItErrorCode - Return MoveItErrorCodes::SUCCESS if solver found a successful solution. Otherwise,
144+ * return an appropriate error type and message explaining why it failed.
133145 */
134- Result plan (const planning_scene::PlanningSceneConstPtr& from, const moveit::core::LinkModel& link,
135- const Eigen::Isometry3d& offset, const Eigen::Isometry3d& target,
136- const moveit::core::JointModelGroup* joint_model_group, double timeout,
137- robot_trajectory::RobotTrajectoryPtr& result,
138- const moveit_msgs::msg::Constraints& path_constraints = moveit_msgs::msg::Constraints()) override ;
139-
140- std::string getPlannerId () const override { return last_successful_planner_; }
146+ MoveItErrorCode
147+ plan (const planning_scene::PlanningSceneConstPtr& from, const moveit::core::LinkModel& link,
148+ const Eigen::Isometry3d& offset, const Eigen::Isometry3d& target,
149+ const moveit::core::JointModelGroup* joint_model_group, double timeout,
150+ robot_trajectory::RobotTrajectoryPtr& result,
151+ const moveit_msgs::msg::Constraints& path_constraints = moveit_msgs::msg::Constraints()) override ;
152+
153+ /* *
154+ * \brief Get planner name
155+ * \return Name of the last successful planner
156+ */
157+ std::string getPlannerId () const override ;
141158
142159protected:
143- /* * \brief Actual plan() implementation, targeting the given goal_constraints.
160+ /* * \brief Function that actually uses the planning pipelines to solve the given planning problem. It is called by
161+ * the public plan function after the goal constraints are generated. This function uses a predefined number of
162+ * planning pipelines in parallel to solve the planning problem and choose the best (user-defined) solution.
144163 * \param [in] planning_scene Scene for which the planning should be solved
145- * \param [in] joint_model_group Group of joints for which this trajectory is created
146- * \param [in] goal_constraints Set of constraints that need to be satisfied by the solution
164+ * \param [in] joint_model_group
165+ * Group of joints for which this trajectory is created
166+ * \param [in] goal_constraints Set of constraints that need to
167+ * be satisfied by the solution
147168 * \param [in] timeout Maximum planning timeout for an individual stage that is using the pipeline planner in seconds
148- * \param [in] result Reference to the location where the created trajectory is stored if planning is successful
149- * \param [in] path_constraints Path contraints for the planning problem
150- * \return true if the solver found a successful solution for the given planning problem
169+ * \param [in] result Reference to the location where the created
170+ * trajectory is stored if planning is successful
171+ * \param [in] path_constraints Path contraints for the planning
172+ * problem
173+ * \return true If the solver found a successful solution for the given planning problem
151174 */
152- Result plan (const planning_scene::PlanningSceneConstPtr& planning_scene,
153- const moveit::core::JointModelGroup* joint_model_group,
154- const moveit_msgs::msg::Constraints& goal_constraints, double timeout,
155- robot_trajectory::RobotTrajectoryPtr& result,
156- const moveit_msgs::msg::Constraints& path_constraints = moveit_msgs::msg::Constraints());
175+ MoveItErrorCode plan (const planning_scene::PlanningSceneConstPtr& planning_scene,
176+ const moveit::core::JointModelGroup* joint_model_group,
177+ const moveit_msgs::msg::Constraints& goal_constraints, double timeout,
178+ robot_trajectory::RobotTrajectoryPtr& result,
179+ const moveit_msgs::msg::Constraints& path_constraints = moveit_msgs::msg::Constraints());
157180
158181 rclcpp::Node::SharedPtr node_;
159182
160183 std::string last_successful_planner_;
161184
162- /* * \brief Map of instantiated (and named) planning pipelines. */
185+ /* * \brief Map of pipeline names (ids) and their corresponding planner ids. The planning problem is solved for every
186+ * pipeline-planner pair in this map. If no pipelines are passed via constructor argument, the pipeline names are
187+ * used to initialize a set of planning pipelines. */
188+ std::unordered_map<std::string, std::string> pipeline_id_planner_id_map_;
189+
190+ /* * \brief Map of pipelines names and planning pipelines. This map is used to quickly search for a requested motion
191+ * planning pipeline when during plan(..) */
163192 std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr> planning_pipelines_;
164193
165194 moveit::planning_pipeline_interfaces::StoppingCriterionFunction stopping_criterion_callback_;
0 commit comments