planning_context_manager.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_OMPL_INTERFACE_PLANNING_CONTEXT_MANAGER_
38 #define MOVEIT_OMPL_INTERFACE_PLANNING_CONTEXT_MANAGER_
39 
44 
45 #include <vector>
46 #include <string>
47 #include <map>
48 
49 namespace ompl_interface
50 {
52 {
53 public:
54  PlanningContextManager(const robot_model::RobotModelConstPtr& kmodel,
55  const constraint_samplers::ConstraintSamplerManagerPtr& csm);
57 
61 
64  {
65  return planner_configs_;
66  }
67 
68  /* \brief Get the maximum number of sampling attempts allowed when sampling states is needed */
69  unsigned int getMaximumStateSamplingAttempts() const
70  {
72  }
73 
74  /* \brief Set the maximum number of sampling attempts allowed when sampling states is needed */
75  void setMaximumStateSamplingAttempts(unsigned int max_state_sampling_attempts)
76  {
77  max_state_sampling_attempts_ = max_state_sampling_attempts;
78  }
79 
80  /* \brief Get the maximum number of sampling attempts allowed when sampling goals is needed */
81  unsigned int getMaximumGoalSamplingAttempts() const
82  {
84  }
85 
86  /* \brief Set the maximum number of sampling attempts allowed when sampling goals is needed */
87  void setMaximumGoalSamplingAttempts(unsigned int max_goal_sampling_attempts)
88  {
89  max_goal_sampling_attempts_ = max_goal_sampling_attempts;
90  }
91 
92  /* \brief Get the maximum number of goal samples */
93  unsigned int getMaximumGoalSamples() const
94  {
95  return max_goal_samples_;
96  }
97 
98  /* \brief Set the maximum number of goal samples */
99  void setMaximumGoalSamples(unsigned int max_goal_samples)
100  {
101  max_goal_samples_ = max_goal_samples;
102  }
103 
104  /* \brief Get the maximum number of planning threads allowed */
105  unsigned int getMaximumPlanningThreads() const
106  {
107  return max_planning_threads_;
108  }
109 
110  /* \brief Set the maximum number of planning threads */
111  void setMaximumPlanningThreads(unsigned int max_planning_threads)
112  {
113  max_planning_threads_ = max_planning_threads;
114  }
115 
116  /* \brief Get the maximum solution segment length */
118  {
120  }
121 
122  /* \brief Set the maximum solution segment length */
124  {
126  }
127 
128  unsigned int getMinimumWaypointCount() const
129  {
131  }
132 
134  void setMinimumWaypointCount(unsigned int mwc)
135  {
137  }
138 
139  const robot_model::RobotModelConstPtr& getRobotModel() const
140  {
141  return kmodel_;
142  }
143 
144  ModelBasedPlanningContextPtr getLastPlanningContext() const;
145 
146  ModelBasedPlanningContextPtr getPlanningContext(const std::string& config,
147  const std::string& factory_type = "") const;
148 
149  ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
151  moveit_msgs::MoveItErrorCodes& error_code) const;
152 
153  void registerPlannerAllocator(const std::string& planner_id, const ConfiguredPlannerAllocator& pa)
154  {
155  known_planners_[planner_id] = pa;
156  }
157 
158  void registerStateSpaceFactory(const ModelBasedStateSpaceFactoryPtr& factory)
159  {
160  state_space_factories_[factory->getType()] = factory;
161  }
162 
163  const std::map<std::string, ConfiguredPlannerAllocator>& getRegisteredPlannerAllocators() const
164  {
165  return known_planners_;
166  }
167 
168  const std::map<std::string, ModelBasedStateSpaceFactoryPtr>& getRegisteredStateSpaceFactories() const
169  {
170  return state_space_factories_;
171  }
172 
174 
175 protected:
176  typedef boost::function<const ModelBasedStateSpaceFactoryPtr&(const std::string&)> StateSpaceFactoryTypeSelector;
177 
178  ConfiguredPlannerAllocator plannerSelector(const std::string& planner) const;
179 
182 
184  ModelBasedPlanningContextPtr getPlanningContext(const planning_interface::PlannerConfigurationSettings& config,
185  const StateSpaceFactoryTypeSelector& factory_selector,
186  const moveit_msgs::MotionPlanRequest& req) const;
187 
188  const ModelBasedStateSpaceFactoryPtr& getStateSpaceFactory1(const std::string& group_name,
189  const std::string& factory_type) const;
190  const ModelBasedStateSpaceFactoryPtr& getStateSpaceFactory2(const std::string& group_name,
191  const moveit_msgs::MotionPlanRequest& req) const;
192 
194  robot_model::RobotModelConstPtr kmodel_;
195 
196  constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_;
197 
198  std::map<std::string, ConfiguredPlannerAllocator> known_planners_;
199  std::map<std::string, ModelBasedStateSpaceFactoryPtr> state_space_factories_;
200 
207 
209  unsigned int max_goal_samples_;
210 
214 
217 
219  unsigned int max_planning_threads_;
220 
224 
228 
229 private:
231  LastPlanningContextPtr last_planning_context_;
232 
234  CachedContextsPtr cached_contexts_;
235 };
236 }
237 
238 #endif
const robot_model::RobotModelConstPtr & getRobotModel() const
boost::function< ConfiguredPlannerAllocator(const std::string &planner_type)> ConfiguredPlannerSelector
void setMaximumPlanningThreads(unsigned int max_planning_threads)
robot_model::RobotModelConstPtr kmodel_
The kinematic model for which motion plans are computed.
ModelBasedPlanningContextPtr getPlanningContext(const std::string &config, const std::string &factory_type="") const
void setMinimumWaypointCount(unsigned int mwc)
Get the minimum number of waypoints along the solution path.
MOVEIT_CLASS_FORWARD(LastPlanningContext)
const std::map< std::string, ConfiguredPlannerAllocator > & getRegisteredPlannerAllocators() const
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
The MoveIt! interface to OMPL.
PlanningContextManager(const robot_model::RobotModelConstPtr &kmodel, const constraint_samplers::ConstraintSamplerManagerPtr &csm)
std::map< std::string, ModelBasedStateSpaceFactoryPtr > state_space_factories_
const ModelBasedStateSpaceFactoryPtr & getStateSpaceFactory2(const std::string &group_name, const moveit_msgs::MotionPlanRequest &req) const
boost::function< ob::PlannerPtr(const ompl::base::SpaceInformationPtr &si, const std::string &name, const ModelBasedPlanningContextSpecification &spec)> ConfiguredPlannerAllocator
void setMaximumStateSamplingAttempts(unsigned int max_state_sampling_attempts)
ConfiguredPlannerSelector getPlannerSelector() const
void registerPlannerAllocator(const std::string &planner_id, const ConfiguredPlannerAllocator &pa)
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
const planning_interface::PlannerConfigurationMap & getPlannerConfigurations() const
Return the previously set planner configurations.
planning_interface::PlannerConfigurationMap planner_configs_
All the existing planning configurations. The name of the configuration is the key of the map...
unsigned int max_planning_threads_
when planning in parallel, this is the maximum number of threads to use at one time ...
ConfiguredPlannerAllocator plannerSelector(const std::string &planner) const
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
Specify configurations for the planners.
unsigned int max_goal_sampling_attempts_
maximum number of attempts to be made at sampling goals
moveit_msgs::MotionPlanRequest MotionPlanRequest
void registerStateSpaceFactory(const ModelBasedStateSpaceFactoryPtr &factory)
void setMaximumGoalSamples(unsigned int max_goal_samples)
const ModelBasedStateSpaceFactoryPtr & getStateSpaceFactory1(const std::string &group_name, const std::string &factory_type) const
unsigned int max_goal_samples_
maximum number of states to sample in the goal region for any planning request (when such sampling is...
ModelBasedPlanningContextPtr getLastPlanningContext() const
boost::function< const ModelBasedStateSpaceFactoryPtr &(const std::string &)> StateSpaceFactoryTypeSelector
std::map< std::string, ConfiguredPlannerAllocator > known_planners_
void setMaximumGoalSamplingAttempts(unsigned int max_goal_sampling_attempts)
const std::map< std::string, ModelBasedStateSpaceFactoryPtr > & getRegisteredStateSpaceFactories() const


ompl
Author(s): Ioan Sucan
autogenerated on Sun Oct 18 2020 13:18:01