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 
42 #include <ros/ros.h>
43 
44 #include <atomic>
45 #include <memory>
46 
49 {
56 class PlanningPipeline
57 {
58 public:
61  static const std::string DISPLAY_PATH_TOPIC;
62 
65  static const std::string MOTION_PLAN_REQUEST_TOPIC;
66 
69  static const std::string MOTION_CONTACTS_TOPIC;
70 
79  PlanningPipeline(const moveit::core::RobotModelConstPtr& model,
80  const ros::NodeHandle& pipeline_nh = ros::NodeHandle("~"),
81  const std::string& planning_plugin_param_name = "planning_plugin",
82  const std::string& adapter_plugins_param_name = "request_adapters");
83 
90  PlanningPipeline(const moveit::core::RobotModelConstPtr& model, const ros::NodeHandle& pipeline_nh,
91  const std::string& planning_plugin_name, const std::vector<std::string>& adapter_plugin_names);
92 
95  void displayComputedMotionPlans(bool flag);
96 
99  void publishReceivedRequests(bool flag);
100 
103  void checkSolutionPaths(bool flag);
104 
106  bool getDisplayComputedMotionPlans() const
107  {
109  }
110 
112  bool getPublishReceivedRequests() const
113  {
115  }
116 
118  bool getCheckSolutionPaths() const
119  {
120  return check_solution_paths_;
121  }
122 
127  bool generatePlan(const planning_scene::PlanningSceneConstPtr& planning_scene,
130 
139  bool generatePlan(const planning_scene::PlanningSceneConstPtr& planning_scene,
141  std::vector<std::size_t>& adapter_added_state_index) const;
142 
144  void terminate() const;
145 
147  const std::string& getPlannerPluginName() const
148  {
149  return planner_plugin_name_;
150  }
151 
153  const std::vector<std::string>& getAdapterPluginNames() const
154  {
155  return adapter_plugin_names_;
156  }
157 
159  const planning_interface::PlannerManagerPtr& getPlannerManager()
160  {
161  return planner_instance_;
162  }
163 
165  const moveit::core::RobotModelConstPtr& getRobotModel() const
166  {
167  return robot_model_;
168  }
169 
171  [[nodiscard]] bool isActive() const
172  {
173  return active_;
174  }
175 
176 private:
177  void configure();
178 
179  // Flag that indicates whether or not the planning pipeline is currently solving a planning problem
180  mutable std::atomic<bool> active_;
181 
182  // The NodeHandle to initialize the PlanningPipeline (parameters plugins) with
184  // The private node handle of the node this PlanningPipeline was initialized from.
185  // It's used for plugin-agnostic display and info topics.
187 
191 
196 
197  std::unique_ptr<pluginlib::ClassLoader<planning_interface::PlannerManager> > planner_plugin_loader_;
198  planning_interface::PlannerManagerPtr planner_instance_;
199  std::string planner_plugin_name_;
200 
201  std::unique_ptr<pluginlib::ClassLoader<planning_request_adapter::PlanningRequestAdapter> > adapter_plugin_loader_;
202  std::unique_ptr<planning_request_adapter::PlanningRequestAdapterChain> adapter_chain_;
203  std::vector<std::string> adapter_plugin_names_;
204 
205  moveit::core::RobotModelConstPtr robot_model_;
206 
210 };
211 
212 MOVEIT_CLASS_FORWARD(PlanningPipeline); // Defines PlanningPipelinePtr, ConstPtr, WeakPtr... etc
213 } // namespace planning_pipeline
planning_pipeline::PlanningPipeline::planner_plugin_name_
std::string planner_plugin_name_
Definition: planning_pipeline.h:263
ros::Publisher
planning_pipeline::PlanningPipeline::DISPLAY_PATH_TOPIC
static const std::string DISPLAY_PATH_TOPIC
When motion plans are computed and they are supposed to be automatically displayed,...
Definition: planning_pipeline.h:125
planning_interface::MotionPlanResponse
planning_pipeline::PlanningPipeline::robot_model_
moveit::core::RobotModelConstPtr robot_model_
Definition: planning_pipeline.h:269
planning_request_adapter.h
ros.h
planning_pipeline::PlanningPipeline::terminate
void terminate() const
Request termination, if a generatePlan() function is currently computing plans.
Definition: planning_pipeline.cpp:385
planning_pipeline::PlanningPipeline::planner_plugin_loader_
std::unique_ptr< pluginlib::ClassLoader< planning_interface::PlannerManager > > planner_plugin_loader_
Definition: planning_pipeline.h:261
planning_pipeline::PlanningPipeline::planner_instance_
planning_interface::PlannerManagerPtr planner_instance_
Definition: planning_pipeline.h:262
planning_pipeline::PlanningPipeline::getAdapterPluginNames
const std::vector< std::string > & getAdapterPluginNames() const
Get the names of the planning request adapter plugins used.
Definition: planning_pipeline.h:217
planning_pipeline::PlanningPipeline::getRobotModel
const moveit::core::RobotModelConstPtr & getRobotModel() const
Get the robot model that this pipeline is using.
Definition: planning_pipeline.h:229
planning_interface.h
planning_pipeline::PlanningPipeline::MOTION_CONTACTS_TOPIC
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 ...
Definition: planning_pipeline.h:133
planning_pipeline::PlanningPipeline::check_solution_paths_
bool check_solution_paths_
Flag indicating whether the reported plans should be checked once again, by the planning pipeline its...
Definition: planning_pipeline.h:272
planning_pipeline::PlanningPipeline::MOTION_PLAN_REQUEST_TOPIC
static const std::string MOTION_PLAN_REQUEST_TOPIC
When motion planning requests are received and they are supposed to be automatically published,...
Definition: planning_pipeline.h:129
planning_pipeline::PlanningPipeline::adapter_plugin_loader_
std::unique_ptr< pluginlib::ClassLoader< planning_request_adapter::PlanningRequestAdapter > > adapter_plugin_loader_
Definition: planning_pipeline.h:265
planning_pipeline::PlanningPipeline::getPublishReceivedRequests
bool getPublishReceivedRequests() const
Get the flag set by publishReceivedRequests()
Definition: planning_pipeline.h:176
planning_pipeline::PlanningPipeline::generatePlan
bool generatePlan(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const
Call the motion planner plugin and the sequence of planning request adapters (if any).
Definition: planning_pipeline.cpp:210
planning_pipeline::PlanningPipeline::checkSolutionPaths
void checkSolutionPaths(bool flag)
Pass a flag telling the pipeline whether or not to re-check the solution paths reported by the planne...
Definition: planning_pipeline.cpp:201
planning_pipeline::PlanningPipeline::PlanningPipeline
PlanningPipeline(const moveit::core::RobotModelConstPtr &model, const ros::NodeHandle &pipeline_nh=ros::NodeHandle("~"), const std::string &planning_plugin_param_name="planning_plugin", const std::string &adapter_plugins_param_name="request_adapters")
Given a robot model (model), a node handle (pipeline_nh), initialize the planning pipeline.
Definition: planning_pipeline.cpp:51
planning_pipeline::PlanningPipeline::configure
void configure()
Definition: planning_pipeline.cpp:87
planning_pipeline::PlanningPipeline::displayComputedMotionPlans
void displayComputedMotionPlans(bool flag)
Pass a flag telling the pipeline whether or not to publish the computed motion plans on DISPLAY_PATH_...
Definition: planning_pipeline.cpp:182
planning_pipeline::PlanningPipeline::publishReceivedRequests
void publishReceivedRequests(bool flag)
Pass a flag telling the pipeline whether or not to publish the received motion planning requests on M...
Definition: planning_pipeline.cpp:191
planning_pipeline::PlanningPipeline::pipeline_nh_
ros::NodeHandle pipeline_nh_
Definition: planning_pipeline.h:247
planning_pipeline::PlanningPipeline::getPlannerManager
const planning_interface::PlannerManagerPtr & getPlannerManager()
Get the planner manager for the loaded planning plugin.
Definition: planning_pipeline.h:223
planning_pipeline::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(PlanningPipeline)
class_loader.hpp
planning_interface::MotionPlanRequest
moveit_msgs::MotionPlanRequest MotionPlanRequest
planning_pipeline::PlanningPipeline::publish_received_requests_
bool publish_received_requests_
Definition: planning_pipeline.h:258
planning_pipeline
Planning pipeline.
Definition: planning_pipeline.h:48
planning_pipeline::PlanningPipeline::getCheckSolutionPaths
bool getCheckSolutionPaths() const
Get the flag set by checkSolutionPaths()
Definition: planning_pipeline.h:182
planning_pipeline::PlanningPipeline::active_
std::atomic< bool > active_
Definition: planning_pipeline.h:244
planning_pipeline::PlanningPipeline::adapter_plugin_names_
std::vector< std::string > adapter_plugin_names_
Definition: planning_pipeline.h:267
planning_pipeline::PlanningPipeline::display_path_publisher_
ros::Publisher display_path_publisher_
Definition: planning_pipeline.h:254
planning_pipeline::PlanningPipeline::isActive
bool isActive() const
Get current status of the planning pipeline.
Definition: planning_pipeline.h:235
planning_pipeline::PlanningPipeline::getDisplayComputedMotionPlans
bool getDisplayComputedMotionPlans() const
Get the flag set by displayComputedMotionPlans()
Definition: planning_pipeline.h:170
planning_pipeline::PlanningPipeline::adapter_chain_
std::unique_ptr< planning_request_adapter::PlanningRequestAdapterChain > adapter_chain_
Definition: planning_pipeline.h:266
planning_scene
planning_pipeline::PlanningPipeline::private_nh_
ros::NodeHandle private_nh_
Definition: planning_pipeline.h:250
planning_pipeline::PlanningPipeline::received_request_publisher_
ros::Publisher received_request_publisher_
Definition: planning_pipeline.h:259
planning_pipeline::PlanningPipeline::display_computed_motion_plans_
bool display_computed_motion_plans_
Flag indicating whether motion plans should be published as a moveit_msgs::DisplayTrajectory.
Definition: planning_pipeline.h:253
planning_pipeline::PlanningPipeline
This class facilitates loading planning plugins and planning request adapted plugins....
Definition: planning_pipeline.h:88
planning_pipeline::PlanningPipeline::contacts_publisher_
ros::Publisher contacts_publisher_
Definition: planning_pipeline.h:273
ros::NodeHandle
planning_pipeline::PlanningPipeline::getPlannerPluginName
const std::string & getPlannerPluginName() const
Get the name of the planning plugin used.
Definition: planning_pipeline.h:211


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Thu Apr 18 2024 02:24:19