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>
48 #include <moveit_planning_pipeline_export.h>
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");
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);
101 void displayComputedMotionPlans(
bool flag);
105 void publishReceivedRequests(
bool flag);
109 void checkSolutionPaths(
bool flag);
114 return display_computed_motion_plans_;
120 return publish_received_requests_;
126 return check_solution_paths_;
133 bool generatePlan(
const planning_scene::PlanningSceneConstPtr&
planning_scene,
145 bool generatePlan(
const planning_scene::PlanningSceneConstPtr&
planning_scene,
147 std::vector<std::size_t>& adapter_added_state_index)
const;
150 void terminate()
const;
155 return planner_plugin_name_;
161 return adapter_plugin_names_;
167 return planner_instance_;
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_;
187 bool publish_received_requests_;
188 rclcpp::Publisher<moveit_msgs::msg::MotionPlanRequest>::SharedPtr received_request_publisher_;
190 std::unique_ptr<pluginlib::ClassLoader<planning_interface::PlannerManager> > planner_plugin_loader_;
191 planning_interface::PlannerManagerPtr planner_instance_;
192 std::string planner_plugin_name_;
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_;
198 moveit::core::RobotModelConstPtr robot_model_;
201 bool check_solution_paths_;
202 rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr contacts_publisher_;
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
MOVEIT_CLASS_FORWARD(PlanningPipeline)
This namespace includes the central class for representing planning contexts.