moveit2
The MoveIt Motion Planning Framework for ROS 2.
planning_pipeline.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, 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 Willow Garage 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: Ioan Sucan */
36 
37 #pragma once
38 
41 #include <pluginlib/class_loader.hpp>
42 #include <rclcpp/rclcpp.hpp>
43 #include <moveit_msgs/msg/display_trajectory.hpp>
44 #include <visualization_msgs/msg/marker_array.hpp>
45 
46 #include <memory>
47 
48 #include <moveit_planning_pipeline_export.h>
49 
51 namespace planning_pipeline
52 {
59 class MOVEIT_PLANNING_PIPELINE_EXPORT PlanningPipeline
60 {
61 public:
64  static const std::string DISPLAY_PATH_TOPIC;
65 
68  static const std::string MOTION_PLAN_REQUEST_TOPIC;
69 
72  static const std::string MOTION_CONTACTS_TOPIC;
73 
83  PlanningPipeline(const moveit::core::RobotModelConstPtr& model, const std::shared_ptr<rclcpp::Node>& node,
84  const std::string& parameter_namespace,
85  const std::string& planning_plugin_param_name = "planning_plugin",
86  const std::string& adapter_plugins_param_name = "request_adapters");
87 
95  PlanningPipeline(const moveit::core::RobotModelConstPtr& model, const std::shared_ptr<rclcpp::Node>& node,
96  const std::string& parameter_namespace, const std::string& planning_plugin_name,
97  const std::vector<std::string>& adapter_plugin_names);
98 
101  void displayComputedMotionPlans(bool flag);
102 
105  void publishReceivedRequests(bool flag);
106 
109  void checkSolutionPaths(bool flag);
110 
113  {
114  return display_computed_motion_plans_;
115  }
116 
119  {
120  return publish_received_requests_;
121  }
122 
125  {
126  return check_solution_paths_;
127  }
128 
133  bool generatePlan(const planning_scene::PlanningSceneConstPtr& planning_scene,
136 
145  bool generatePlan(const planning_scene::PlanningSceneConstPtr& planning_scene,
147  std::vector<std::size_t>& adapter_added_state_index) const;
148 
150  void terminate() const;
151 
153  const std::string& getPlannerPluginName() const
154  {
155  return planner_plugin_name_;
156  }
157 
159  const std::vector<std::string>& getAdapterPluginNames() const
160  {
161  return adapter_plugin_names_;
162  }
163 
165  const planning_interface::PlannerManagerPtr& getPlannerManager()
166  {
167  return planner_instance_;
168  }
169 
171  const moveit::core::RobotModelConstPtr& getRobotModel() const
172  {
173  return robot_model_;
174  }
175 
176 private:
177  void configure();
178 
179  std::shared_ptr<rclcpp::Node> node_;
180  std::string parameter_namespace_;
182  bool display_computed_motion_plans_;
183  rclcpp::Publisher<moveit_msgs::msg::DisplayTrajectory>::SharedPtr display_path_publisher_;
184 
187  bool publish_received_requests_;
188  rclcpp::Publisher<moveit_msgs::msg::MotionPlanRequest>::SharedPtr received_request_publisher_;
189 
190  std::unique_ptr<pluginlib::ClassLoader<planning_interface::PlannerManager> > planner_plugin_loader_;
191  planning_interface::PlannerManagerPtr planner_instance_;
192  std::string planner_plugin_name_;
193 
194  std::unique_ptr<pluginlib::ClassLoader<planning_request_adapter::PlanningRequestAdapter> > adapter_plugin_loader_;
195  std::unique_ptr<planning_request_adapter::PlanningRequestAdapterChain> adapter_chain_;
196  std::vector<std::string> adapter_plugin_names_;
197 
198  moveit::core::RobotModelConstPtr robot_model_;
199 
201  bool check_solution_paths_;
202  rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr contacts_publisher_;
203 };
204 
205 MOVEIT_CLASS_FORWARD(PlanningPipeline); // Defines PlanningPipelinePtr, ConstPtr, WeakPtr... etc
206 } // namespace planning_pipeline
This class facilitates loading planning plugins and planning request adapted plugins....
const std::vector< std::string > & getAdapterPluginNames() const
Get the names of the planning request adapter plugins used.
bool getCheckSolutionPaths() const
Get the flag set by checkSolutionPaths()
const planning_interface::PlannerManagerPtr & getPlannerManager()
Get the planner manager for the loaded planning plugin.
static const std::string MOTION_PLAN_REQUEST_TOPIC
When motion planning requests are received and they are supposed to be automatically published,...
const std::string & getPlannerPluginName() const
Get the name of the planning plugin used.
const moveit::core::RobotModelConstPtr & getRobotModel() const
Get the robot model that this pipeline is using.
bool getDisplayComputedMotionPlans() const
Get the flag set by displayComputedMotionPlans()
bool getPublishReceivedRequests() const
Get the flag set by publishReceivedRequests()
static const std::string MOTION_CONTACTS_TOPIC
When contacts are found in the solution path reported by a planner, they can be published as markers ...
static const std::string DISPLAY_PATH_TOPIC
When motion plans are computed and they are supposed to be automatically displayed,...
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
Planning pipeline.
MOVEIT_CLASS_FORWARD(PlanningPipeline)
This namespace includes the central class for representing planning contexts.