planning_interface.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_INTERFACE_PLANNING_INTERFACE_
38 #define MOVEIT_PLANNING_INTERFACE_PLANNING_INTERFACE_
39 
43 #include <string>
44 #include <map>
45 
46 namespace planning_scene
47 {
49 }
50 
53 {
60 {
62  std::string group;
63 
64  /* \brief Name of the configuration.
65 
66  For a group's default configuration, this should be the same as the group name.
67  Otherwise, the form "group_name[config_name]" is expected for the name. */
68  std::string name;
69 
71  std::map<std::string, std::string> config;
72 };
73 
75 typedef std::map<std::string, PlannerConfigurationSettings> PlannerConfigurationMap;
76 
78 
82 {
83 public:
85  PlanningContext(const std::string& name, const std::string& group);
86 
87  virtual ~PlanningContext();
88 
90  const std::string& getGroupName() const
91  {
92  return group_;
93  }
94 
96  const std::string& getName() const
97  {
98  return name_;
99  }
100 
102  const planning_scene::PlanningSceneConstPtr& getPlanningScene() const
103  {
104  return planning_scene_;
105  }
106 
109  {
110  return request_;
111  }
112 
114  void setPlanningScene(const planning_scene::PlanningSceneConstPtr& planning_scene);
115 
117  void setMotionPlanRequest(const MotionPlanRequest& request);
118 
121  virtual bool solve(MotionPlanResponse& res) = 0;
122 
125  virtual bool solve(MotionPlanDetailedResponse& res) = 0;
126 
129  virtual bool terminate() = 0;
130 
132  virtual void clear() = 0;
133 
134 protected:
136  std::string name_;
137 
139  std::string group_;
140 
142  planning_scene::PlanningSceneConstPtr planning_scene_;
143 
146 };
147 
149 
152 {
153 public:
155  {
156  }
157 
158  virtual ~PlannerManager()
159  {
160  }
161 
167  virtual bool initialize(const robot_model::RobotModelConstPtr& model, const std::string& ns);
168 
170  virtual std::string getDescription() const;
171 
174  virtual void getPlanningAlgorithms(std::vector<std::string>& algs) const;
175 
183  virtual PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
184  const MotionPlanRequest& req,
185  moveit_msgs::MoveItErrorCodes& error_code) const = 0;
186 
188  PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
189  const MotionPlanRequest& req) const;
190 
192  virtual bool canServiceRequest(const MotionPlanRequest& req) const = 0;
193 
195  virtual void setPlannerConfigurations(const PlannerConfigurationMap& pcs);
196 
198  const PlannerConfigurationMap& getPlannerConfigurations() const
199  {
200  return config_settings_;
201  }
202 
204  void terminate() const;
205 
206 protected:
212  PlannerConfigurationMap config_settings_;
213 };
214 
215 } // planning_interface
216 
217 #endif
MOVEIT_CLASS_FORWARD(PlanningScene)
ROSCONSOLE_DECL void initialize()
Specify the settings for a particular planning algorithm, for a particular group. The Planner plugin ...
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
Map from PlannerConfigurationSettings.name to PlannerConfigurationSettings.
const PlannerConfigurationMap & getPlannerConfigurations() const
Get the settings for a specific algorithm.
std::map< std::string, std::string > config
Key-value pairs of settings that get passed to the planning algorithm.
Representation of a particular planning context – the planning scene and the request are known...
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
Get the planning scene associated to this planning context.
std::string group_
The group (as in the SRDF) this planning context is for.
planning_scene::PlanningSceneConstPtr planning_scene_
The planning scene for this context.
This class maintains the representation of the environment as seen by a planning instance. The environment geometry, the robot geometry and state are maintained.
const std::string & getGroupName() const
Get the name of the group this planning context is for.
This namespace includes the central class for representing planning contexts.
moveit_msgs::MotionPlanRequest MotionPlanRequest
const MotionPlanRequest & getMotionPlanRequest() const
Get the motion plan request associated to this planning context.
const std::string & getName() const
Get the name of this planning context.
std::string group
The group (as defined in the SRDF) this configuration is meant for.
std::string name_
The name of this planning context.
This namespace includes the base class for MoveIt! planners.
MotionPlanRequest request_
The planning request for this context.
Base class for a MoveIt! planner.
PlannerConfigurationMap config_settings_
All the existing planning configurations. The name of the configuration is the key of the map...


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jul 10 2019 04:03:05