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 #ifndef MOVEIT_PLANNING_PIPELINE_PLANNING_PIPELINE_
38 #define MOVEIT_PLANNING_PIPELINE_PLANNING_PIPELINE_
39 
43 #include <ros/ros.h>
44 
45 #include <memory>
46 
49 {
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 robot_model::RobotModelConstPtr& model, const ros::NodeHandle& nh = ros::NodeHandle("~"),
80  const std::string& planning_plugin_param_name = "planning_plugin",
81  const std::string& adapter_plugins_param_name = "request_adapters");
82 
89  PlanningPipeline(const robot_model::RobotModelConstPtr& model, const ros::NodeHandle& nh,
90  const std::string& planning_plugin_name, const std::vector<std::string>& adapter_plugin_names);
91 
94  void displayComputedMotionPlans(bool flag);
95 
98  void publishReceivedRequests(bool flag);
99 
102  void checkSolutionPaths(bool flag);
103 
106  {
108  }
109 
112  {
114  }
115 
118  {
119  return check_solution_paths_;
120  }
121 
126  bool generatePlan(const planning_scene::PlanningSceneConstPtr& planning_scene,
129 
138  bool generatePlan(const planning_scene::PlanningSceneConstPtr& planning_scene,
140  std::vector<std::size_t>& adapter_added_state_index) const;
141 
143  void terminate() const;
144 
146  const std::string& getPlannerPluginName() const
147  {
148  return planner_plugin_name_;
149  }
150 
152  const std::vector<std::string>& getAdapterPluginNames() const
153  {
154  return adapter_plugin_names_;
155  }
156 
158  const planning_interface::PlannerManagerPtr& getPlannerManager()
159  {
160  return planner_instance_;
161  }
162 
164  const robot_model::RobotModelConstPtr& getRobotModel() const
165  {
166  return kmodel_;
167  }
168 
169 private:
170  void configure();
171 
173 
177 
182 
183  std::unique_ptr<pluginlib::ClassLoader<planning_interface::PlannerManager> > planner_plugin_loader_;
184  planning_interface::PlannerManagerPtr planner_instance_;
185  std::string planner_plugin_name_;
186 
187  std::unique_ptr<pluginlib::ClassLoader<planning_request_adapter::PlanningRequestAdapter> > adapter_plugin_loader_;
188  std::unique_ptr<planning_request_adapter::PlanningRequestAdapterChain> adapter_chain_;
189  std::vector<std::string> adapter_plugin_names_;
190 
191  robot_model::RobotModelConstPtr kmodel_;
192 
196 };
197 
199 }
200 
201 #endif
const std::string & getPlannerPluginName() const
Get the name of the planning plugin used.
static const std::string MOTION_PLAN_REQUEST_TOPIC
When motion planning requests are received and they are supposed to be automatically published...
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).
bool getDisplayComputedMotionPlans() const
Get the flag set by displayComputedMotionPlans()
std::unique_ptr< planning_request_adapter::PlanningRequestAdapterChain > adapter_chain_
void publishReceivedRequests(bool flag)
Pass a flag telling the pipeline whether or not to publish the received motion planning requests on M...
void displayComputedMotionPlans(bool flag)
Pass a flag telling the pipeline whether or not to publish the computed motion plans on DISPLAY_PATH_...
Planning pipeline.
void terminate() const
Request termination, if a generatePlan() function is currently computing plans.
std::vector< std::string > adapter_plugin_names_
This class facilitates loading planning plugins and planning request adapted plugins. and allows calling planning_interface::PlanningContext::solve() from a loaded planning plugin and the planning_request_adapter::PlanningRequestAdapter plugins, in the specified order.
robot_model::RobotModelConstPtr kmodel_
void checkSolutionPaths(bool flag)
Pass a flag telling the pipeline whether or not to re-check the solution paths reported by the planne...
const robot_model::RobotModelConstPtr & getRobotModel() const
Get the robot model that this pipeline is using.
bool check_solution_paths_
Flag indicating whether the reported plans should be checked once again, by the planning pipeline its...
moveit_msgs::MotionPlanRequest MotionPlanRequest
static const std::string DISPLAY_PATH_TOPIC
When motion plans are computed and they are supposed to be automatically displayed, they are sent to this topic (moveit_msgs::DisplauTrajectory)
std::unique_ptr< pluginlib::ClassLoader< planning_interface::PlannerManager > > planner_plugin_loader_
bool display_computed_motion_plans_
Flag indicating whether motion plans should be published as a moveit_msgs::DisplayTrajectory.
planning_interface::PlannerManagerPtr planner_instance_
const std::vector< std::string > & getAdapterPluginNames() const
Get the names of the planning request adapter plugins used.
MOVEIT_CLASS_FORWARD(PlanningPipeline)
const planning_interface::PlannerManagerPtr & getPlannerManager()
Get the planner manager for the loaded planning plugin.
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 ...
bool getCheckSolutionPaths() const
Get the flag set by checkSolutionPaths()
std::unique_ptr< pluginlib::ClassLoader< planning_request_adapter::PlanningRequestAdapter > > adapter_plugin_loader_
PlanningPipeline(const robot_model::RobotModelConstPtr &model, const ros::NodeHandle &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 (nh), initialize the planning pipeline.
bool getPublishReceivedRequests() const
Get the flag set by publishReceivedRequests()


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Wed Jul 10 2019 04:03:32