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 #pragma once
38 
42 #include <string>
43 #include <map>
44 
45 namespace planning_scene
46 {
47 MOVEIT_CLASS_FORWARD(PlanningScene); // Defines PlanningScenePtr, ConstPtr, WeakPtr... etc
48 }
49 
52 {
59 {
61  std::string group;
62 
63  /* \brief Name of the configuration.
64 
65  For a group's default configuration, this should be the same as the group name.
66  Otherwise, the form "group_name[config_name]" is expected for the name. */
67  std::string name;
68 
70  std::map<std::string, std::string> config;
71 };
72 
74 typedef std::map<std::string, PlannerConfigurationSettings> PlannerConfigurationMap;
75 
76 MOVEIT_CLASS_FORWARD(PlanningContext); // Defines PlanningContextPtr, ConstPtr, WeakPtr... etc
77 
81 {
82 public:
84  PlanningContext(const std::string& name, const std::string& group);
85 
86  virtual ~PlanningContext();
87 
89  const std::string& getGroupName() const
90  {
91  return group_;
92  }
93 
95  const std::string& getName() const
96  {
97  return name_;
98  }
99 
101  const planning_scene::PlanningSceneConstPtr& getPlanningScene() const
102  {
103  return planning_scene_;
104  }
105 
108  {
109  return request_;
110  }
111 
113  void setPlanningScene(const planning_scene::PlanningSceneConstPtr& planning_scene);
114 
116  void setMotionPlanRequest(const MotionPlanRequest& request);
117 
120  virtual bool solve(MotionPlanResponse& res) = 0;
121 
124  virtual bool solve(MotionPlanDetailedResponse& res) = 0;
125 
128  virtual bool terminate() = 0;
129 
131  virtual void clear() = 0;
132 
133 protected:
135  std::string name_;
136 
138  std::string group_;
139 
141  planning_scene::PlanningSceneConstPtr planning_scene_;
142 
145 };
146 
147 MOVEIT_CLASS_FORWARD(PlannerManager); // Defines PlannerManagerPtr, ConstPtr, WeakPtr... etc
148 
151 {
152 public:
154  {
155  }
156 
157  virtual ~PlannerManager()
158  {
159  }
160 
166  virtual bool initialize(const moveit::core::RobotModelConstPtr& model, const std::string& ns);
167 
169  virtual std::string getDescription() const;
170 
173  virtual void getPlanningAlgorithms(std::vector<std::string>& algs) const;
174 
182  virtual PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
183  const MotionPlanRequest& req,
184  moveit_msgs::MoveItErrorCodes& error_code) const = 0;
185 
187  PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
188  const MotionPlanRequest& req) const;
189 
191  virtual bool canServiceRequest(const MotionPlanRequest& req) const = 0;
192 
194  virtual void setPlannerConfigurations(const PlannerConfigurationMap& pcs);
195 
198  {
199  return config_settings_;
200  }
201 
203  void terminate() const;
204 
205 protected:
212 };
213 
214 } // namespace planning_interface
planning_interface::PlannerManager::terminate
void terminate() const
Request termination, if a solve() function is currently computing plans.
Definition: planning_interface.cpp:154
planning_interface::PlanningContext::solve
virtual bool solve(MotionPlanResponse &res)=0
Solve the motion planning problem and store the result in res. This function should not clear data st...
planning_interface::PlannerManager::getPlanningContext
virtual PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const MotionPlanRequest &req, moveit_msgs::MoveItErrorCodes &error_code) const =0
Construct a planning context given the current scene and a planning request. If a problem is encounte...
planning_interface::PlanningContext::terminate
virtual bool terminate()=0
If solve() is running, terminate the computation. Return false if termination not possible....
planning_interface::MotionPlanResponse
Definition: planning_response.h:78
planning_interface::PlanningContext::clear
virtual void clear()=0
Clear the data structures used by the planner.
planning_interface::PlannerManager::getPlanningAlgorithms
virtual void getPlanningAlgorithms(std::vector< std::string > &algs) const
Get the names of the known planning algorithms (values that can be filled as planner_id in the planni...
Definition: planning_interface.cpp:143
class_forward.h
planning_interface::PlannerManager::canServiceRequest
virtual bool canServiceRequest(const MotionPlanRequest &req) const =0
Determine whether this plugin instance is able to represent this planning request.
planning_interface::PlannerManager::~PlannerManager
virtual ~PlannerManager()
Definition: planning_interface.h:157
planning_interface::PlannerConfigurationMap
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
Map from PlannerConfigurationSettings.name to PlannerConfigurationSettings.
Definition: planning_interface.h:74
planning_interface::PlannerConfigurationSettings::name
std::string name
Definition: planning_interface.h:67
planning_interface::PlannerManager::initialize
virtual bool initialize(const moveit::core::RobotModelConstPtr &model, const std::string &ns)
Definition: planning_interface.cpp:126
planning_interface::PlannerManager::setPlannerConfigurations
virtual void setPlannerConfigurations(const PlannerConfigurationMap &pcs)
Specify the settings to be used for specific algorithms.
Definition: planning_interface.cpp:149
planning_interface::PlanningContext::getGroupName
const std::string & getGroupName() const
Get the name of the group this planning context is for.
Definition: planning_interface.h:89
planning_interface::PlanningContext::planning_scene_
planning_scene::PlanningSceneConstPtr planning_scene_
The planning scene for this context.
Definition: planning_interface.h:141
planning_interface::PlanningContext::group_
std::string group_
The group (as in the SRDF) this planning context is for.
Definition: planning_interface.h:138
planning_interface::PlannerManager::PlannerManager
PlannerManager()
Definition: planning_interface.h:153
planning_scene::PlanningScene
This class maintains the representation of the environment as seen by a planning instance....
Definition: planning_scene.h:202
name
std::string name
planning_scene::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(PlanningScene)
planning_interface::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(PlanningContext)
planning_interface::PlannerConfigurationSettings::config
std::map< std::string, std::string > config
Key-value pairs of settings that get passed to the planning algorithm.
Definition: planning_interface.h:70
planning_interface::PlanningContext::getName
const std::string & getName() const
Get the name of this planning context.
Definition: planning_interface.h:95
planning_interface::PlanningContext::setPlanningScene
void setPlanningScene(const planning_scene::PlanningSceneConstPtr &planning_scene)
Set the planning scene for this context.
Definition: planning_interface.cpp:105
planning_interface::MotionPlanRequest
moveit_msgs::MotionPlanRequest MotionPlanRequest
Definition: planning_request.h:77
planning_request.h
planning_interface::PlannerManager::getDescription
virtual std::string getDescription() const
Get.
Definition: planning_interface.cpp:131
planning_interface::PlannerManager::getPlannerConfigurations
const PlannerConfigurationMap & getPlannerConfigurations() const
Get the settings for a specific algorithm.
Definition: planning_interface.h:197
planning_interface::PlanningContext::getPlanningScene
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
Get the planning scene associated to this planning context.
Definition: planning_interface.h:101
planning_interface::PlanningContext::~PlanningContext
virtual ~PlanningContext()
Definition: planning_interface.cpp:98
planning_interface
This namespace includes the base class for MoveIt planners.
Definition: planning_interface.h:51
planning_interface::PlanningContext::name_
std::string name_
The name of this planning context.
Definition: planning_interface.h:135
planning_interface::PlanningContext::PlanningContext
PlanningContext(const std::string &name, const std::string &group)
Construct a planning context named name for the group group.
Definition: planning_interface.cpp:91
planning_interface::PlanningContext::request_
MotionPlanRequest request_
The planning request for this context.
Definition: planning_interface.h:144
planning_response.h
planning_interface::PlanningContext
Representation of a particular planning context – the planning scene and the request are known,...
Definition: planning_interface.h:80
planning_interface::PlannerConfigurationSettings
Specify the settings for a particular planning algorithm, for a particular group. The Planner plugin ...
Definition: planning_interface.h:58
planning_interface::PlanningContext::getMotionPlanRequest
const MotionPlanRequest & getMotionPlanRequest() const
Get the motion plan request associated to this planning context.
Definition: planning_interface.h:107
planning_interface::PlannerConfigurationSettings::group
std::string group
The group (as defined in the SRDF) this configuration is meant for.
Definition: planning_interface.h:61
planning_scene
This namespace includes the central class for representing planning scenes.
Definition: planning_interface.h:45
planning_interface::PlannerManager
Base class for a MoveIt planner.
Definition: planning_interface.h:150
planning_interface::PlannerManager::config_settings_
PlannerConfigurationMap config_settings_
All the existing planning configurations. The name of the configuration is the key of the map....
Definition: planning_interface.h:211
planning_interface::PlanningContext::setMotionPlanRequest
void setMotionPlanRequest(const MotionPlanRequest &request)
Set the planning request for this context.
Definition: planning_interface.cpp:110
planning_interface::MotionPlanDetailedResponse
Definition: planning_response.h:127


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sat Apr 27 2024 02:25:25