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 #pragma once
38 
43 
44 #include <ompl/base/PlannerDataStorage.h>
45 
46 #include <string>
47 #include <map>
48 
49 namespace ompl_interface
50 {
51 class MultiQueryPlannerAllocator
52 {
53 public:
54  MultiQueryPlannerAllocator() = default;
56 
57  template <typename T>
58  ob::PlannerPtr allocatePlanner(const ob::SpaceInformationPtr& si, const std::string& new_name,
59  const ModelBasedPlanningContextSpecification& spec);
60 
61 private:
62  template <typename T>
63  ob::PlannerPtr allocatePlannerImpl(const ob::SpaceInformationPtr& si, const std::string& new_name,
64  const ModelBasedPlanningContextSpecification& spec, bool load_planner_data = false,
65  bool store_planner_data = false, const std::string& file_path = "");
66 
67  template <typename T>
68  inline ob::Planner* allocatePersistentPlanner(const ob::PlannerData& data);
69 
70  // Storing multi-query planners
71  std::map<std::string, ob::PlannerPtr> planners_;
72 
73  std::map<std::string, std::string> planner_data_storage_paths_;
74 
75  // Store and load planner data
76  ob::PlannerDataStorage storage_;
77 };
78 
79 class PlanningContextManager
80 {
81 public:
82  PlanningContextManager(moveit::core::RobotModelConstPtr robot_model,
83  constraint_samplers::ConstraintSamplerManagerPtr csm);
85 
89 
92  {
93  return planner_configs_;
94  }
95 
96  /* \brief Get the maximum number of sampling attempts allowed when sampling states is needed */
97  unsigned int getMaximumStateSamplingAttempts() const
98  {
100  }
101 
102  /* \brief Set the maximum number of sampling attempts allowed when sampling states is needed */
103  void setMaximumStateSamplingAttempts(unsigned int max_state_sampling_attempts)
104  {
105  max_state_sampling_attempts_ = max_state_sampling_attempts;
106  }
107 
108  /* \brief Get the maximum number of sampling attempts allowed when sampling goals is needed */
109  unsigned int getMaximumGoalSamplingAttempts() const
110  {
112  }
113 
114  /* \brief Set the maximum number of sampling attempts allowed when sampling goals is needed */
115  void setMaximumGoalSamplingAttempts(unsigned int max_goal_sampling_attempts)
116  {
117  max_goal_sampling_attempts_ = max_goal_sampling_attempts;
118  }
119 
120  /* \brief Get the maximum number of goal samples */
121  unsigned int getMaximumGoalSamples() const
122  {
124  }
125 
126  /* \brief Set the maximum number of goal samples */
127  void setMaximumGoalSamples(unsigned int max_goal_samples)
128  {
129  max_goal_samples_ = max_goal_samples;
130  }
131 
132  /* \brief Get the maximum number of planning threads allowed */
133  unsigned int getMaximumPlanningThreads() const
134  {
136  }
137 
138  /* \brief Set the maximum number of planning threads */
139  void setMaximumPlanningThreads(unsigned int max_planning_threads)
140  {
141  max_planning_threads_ = max_planning_threads;
142  }
143 
144  /* \brief Get the maximum solution segment length */
145  double getMaximumSolutionSegmentLength() const
146  {
148  }
149 
150  /* \brief Set the maximum solution segment length */
151  void setMaximumSolutionSegmentLength(double mssl)
152  {
154  }
155 
156  unsigned int getMinimumWaypointCount() const
157  {
159  }
160 
162  void setMinimumWaypointCount(unsigned int mwc)
163  {
165  }
166 
167  const moveit::core::RobotModelConstPtr& getRobotModel() const
168  {
169  return robot_model_;
170  }
171 
181  ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
183  moveit_msgs::MoveItErrorCodes& error_code, const ros::NodeHandle& nh,
184  bool use_constraints_approximations) const;
185 
186  void registerPlannerAllocator(const std::string& planner_id, const ConfiguredPlannerAllocator& pa)
187  {
188  known_planners_[planner_id] = pa;
189  }
190 
191  void registerStateSpaceFactory(const ModelBasedStateSpaceFactoryPtr& factory)
192  {
193  state_space_factories_[factory->getType()] = factory;
194  }
195 
196  const std::map<std::string, ConfiguredPlannerAllocator>& getRegisteredPlannerAllocators() const
197  {
198  return known_planners_;
199  }
200 
201  const std::map<std::string, ModelBasedStateSpaceFactoryPtr>& getRegisteredStateSpaceFactories() const
202  {
203  return state_space_factories_;
204  }
205 
207 
208 protected:
209  ConfiguredPlannerAllocator plannerSelector(const std::string& planner) const;
210 
213 
214  template <typename T>
215  void registerPlannerAllocatorHelper(const std::string& planner_id);
216 
218  ModelBasedPlanningContextPtr getPlanningContext(const planning_interface::PlannerConfigurationSettings& config,
219  const ModelBasedStateSpaceFactoryPtr& factory) const;
220 
221  const ModelBasedStateSpaceFactoryPtr& getStateSpaceFactory(const std::string& factory_type) const;
222  const ModelBasedStateSpaceFactoryPtr& getStateSpaceFactory(const std::string& group_name,
223  const moveit_msgs::MotionPlanRequest& req) const;
224 
226  moveit::core::RobotModelConstPtr robot_model_;
227 
228  constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_;
229 
230  std::map<std::string, ConfiguredPlannerAllocator> known_planners_;
231  std::map<std::string, ModelBasedStateSpaceFactoryPtr> state_space_factories_;
232 
239 
241  unsigned int max_goal_samples_;
242 
245  unsigned int max_state_sampling_attempts_;
246 
248  unsigned int max_goal_sampling_attempts_;
249 
251  unsigned int max_planning_threads_;
252 
256 
259  unsigned int minimum_waypoint_count_;
260 
263 
264 private:
266  CachedContextsPtr cached_contexts_;
267 };
268 } // namespace ompl_interface
ompl_interface::PlanningContextManager::setMaximumSolutionSegmentLength
void setMaximumSolutionSegmentLength(double mssl)
Definition: planning_context_manager.h:183
ompl_interface::PlanningContextManager::getRegisteredStateSpaceFactories
const std::map< std::string, ModelBasedStateSpaceFactoryPtr > & getRegisteredStateSpaceFactories() const
Definition: planning_context_manager.h:233
ompl_interface::MultiQueryPlannerAllocator::planners_
std::map< std::string, ob::PlannerPtr > planners_
Definition: planning_context_manager.h:135
ompl_interface::PlanningContextManager::getMinimumWaypointCount
unsigned int getMinimumWaypointCount() const
Definition: planning_context_manager.h:188
ompl_interface::MultiQueryPlannerAllocator::~MultiQueryPlannerAllocator
~MultiQueryPlannerAllocator()
Definition: planning_context_manager.cpp:97
ompl_interface::PlanningContextManager::getStateSpaceFactory
const ModelBasedStateSpaceFactoryPtr & getStateSpaceFactory(const std::string &factory_type) const
Definition: planning_context_manager.cpp:383
ompl_interface::PlanningContextManager::state_space_factories_
std::map< std::string, ModelBasedStateSpaceFactoryPtr > state_space_factories_
Definition: planning_context_manager.h:263
ompl_interface::PlanningContextManager::getRegisteredPlannerAllocators
const std::map< std::string, ConfiguredPlannerAllocator > & getRegisteredPlannerAllocators() const
Definition: planning_context_manager.h:228
model_based_planning_context.h
ompl_interface::PlanningContextManager::registerDefaultStateSpaces
void registerDefaultStateSpaces()
Definition: planning_context_manager.cpp:310
ompl_interface::PlanningContextManager::setMaximumPlanningThreads
void setMaximumPlanningThreads(unsigned int max_planning_threads)
Definition: planning_context_manager.h:171
ompl_interface::PlanningContextManager::max_goal_sampling_attempts_
unsigned int max_goal_sampling_attempts_
maximum number of attempts to be made at sampling goals
Definition: planning_context_manager.h:280
ompl_interface::MultiQueryPlannerAllocator::allocatePersistentPlanner
ob::Planner * allocatePersistentPlanner(const ob::PlannerData &data)
ompl_interface::PlanningContextManager::robot_model_
moveit::core::RobotModelConstPtr robot_model_
The kinematic model for which motion plans are computed.
Definition: planning_context_manager.h:258
ompl_interface::PlanningContextManager::registerPlannerAllocator
void registerPlannerAllocator(const std::string &planner_id, const ConfiguredPlannerAllocator &pa)
Definition: planning_context_manager.h:218
ompl_interface
The MoveIt interface to OMPL.
Definition: constrained_goal_sampler.h:46
ompl_interface::PlanningContextManager::constraint_sampler_manager_
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
Definition: planning_context_manager.h:260
ompl_interface::PlanningContextManager::setMaximumGoalSamplingAttempts
void setMaximumGoalSamplingAttempts(unsigned int max_goal_sampling_attempts)
Definition: planning_context_manager.h:147
ompl_interface::PlanningContextManager::planner_configs_
planning_interface::PlannerConfigurationMap planner_configs_
All the existing planning configurations. The name of the configuration is the key of the map....
Definition: planning_context_manager.h:270
planning_interface::PlannerConfigurationMap
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
ompl_interface::PlanningContextManager::getMaximumSolutionSegmentLength
double getMaximumSolutionSegmentLength() const
Definition: planning_context_manager.h:177
ompl_interface::PlanningContextManager::cached_contexts_
CachedContextsPtr cached_contexts_
Definition: planning_context_manager.h:298
ompl_interface::PlanningContextManager::setMinimumWaypointCount
void setMinimumWaypointCount(unsigned int mwc)
Get the minimum number of waypoints along the solution path.
Definition: planning_context_manager.h:194
ompl_interface::PlanningContextManager::max_solution_segment_length_
double max_solution_segment_length_
Definition: planning_context_manager.h:287
ompl_interface::PlanningContextManager::setPlannerConfigurations
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
Specify configurations for the planners.
Definition: planning_context_manager.cpp:321
ompl_interface::ConfiguredPlannerSelector
std::function< ConfiguredPlannerAllocator(const std::string &planner_type)> ConfiguredPlannerSelector
Definition: model_based_planning_context.h:93
ompl_interface::PlanningContextManager::getPlannerConfigurations
const planning_interface::PlannerConfigurationMap & getPlannerConfigurations() const
Return the previously set planner configurations.
Definition: planning_context_manager.h:123
ompl_interface::MultiQueryPlannerAllocator::allocatePlanner
ob::PlannerPtr allocatePlanner(const ob::SpaceInformationPtr &si, const std::string &new_name, const ModelBasedPlanningContextSpecification &spec)
ompl_interface::MultiQueryPlannerAllocator::allocatePlannerImpl
ob::PlannerPtr allocatePlannerImpl(const ob::SpaceInformationPtr &si, const std::string &new_name, const ModelBasedPlanningContextSpecification &spec, bool load_planner_data=false, bool store_planner_data=false, const std::string &file_path="")
ompl_interface::PlanningContextManager::getPlanningContext
ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::MoveItErrorCodes &error_code, const ros::NodeHandle &nh, bool use_constraints_approximations) const
Returns a planning context to OMPLInterface, which in turn passes it to OMPLPlannerManager.
Definition: planning_context_manager.cpp:427
ompl_interface::PlanningContextManager::getRobotModel
const moveit::core::RobotModelConstPtr & getRobotModel() const
Definition: planning_context_manager.h:199
ompl_interface::PlanningContextManager::max_state_sampling_attempts_
unsigned int max_state_sampling_attempts_
Definition: planning_context_manager.h:277
ompl_interface::PlanningContextManager::max_goal_samples_
unsigned int max_goal_samples_
maximum number of states to sample in the goal region for any planning request (when such sampling is...
Definition: planning_context_manager.h:273
ompl_interface::PlanningContextManager::getMaximumGoalSamplingAttempts
unsigned int getMaximumGoalSamplingAttempts() const
Definition: planning_context_manager.h:141
ompl_interface::PlanningContextManager::getMaximumPlanningThreads
unsigned int getMaximumPlanningThreads() const
Definition: planning_context_manager.h:165
ompl_interface::PlanningContextManager::~PlanningContextManager
~PlanningContextManager()
ompl_interface::PlanningContextManager::PlanningContextManager
PlanningContextManager(moveit::core::RobotModelConstPtr robot_model, constraint_samplers::ConstraintSamplerManagerPtr csm)
Definition: planning_context_manager.cpp:235
ompl_interface::PlanningContextManager::planner_allocator_
MultiQueryPlannerAllocator planner_allocator_
Multi-query planner allocator.
Definition: planning_context_manager.h:294
planning_interface::MotionPlanRequest
moveit_msgs::MotionPlanRequest MotionPlanRequest
ompl_interface::PlanningContextManager::plannerSelector
ConfiguredPlannerAllocator plannerSelector(const std::string &planner) const
Definition: planning_context_manager.cpp:254
ompl_interface::MultiQueryPlannerAllocator
Definition: planning_context_manager.h:83
ompl_interface::PlanningContextManager::CachedContexts
Definition: planning_context_manager.cpp:89
ompl_interface::PlanningContextManager::registerStateSpaceFactory
void registerStateSpaceFactory(const ModelBasedStateSpaceFactoryPtr &factory)
Definition: planning_context_manager.h:223
ompl_interface::PlanningContextManager::getPlannerSelector
ConfiguredPlannerSelector getPlannerSelector() const
Definition: planning_context_manager.cpp:316
ompl_interface::PlanningContextManager::known_planners_
std::map< std::string, ConfiguredPlannerAllocator > known_planners_
Definition: planning_context_manager.h:262
ompl_interface::PlanningContextManager::max_planning_threads_
unsigned int max_planning_threads_
when planning in parallel, this is the maximum number of threads to use at one time
Definition: planning_context_manager.h:283
constraint_sampler_manager.h
class_forward.h
ompl_interface::MultiQueryPlannerAllocator::MultiQueryPlannerAllocator
MultiQueryPlannerAllocator()=default
ompl_interface::ConfiguredPlannerAllocator
std::function< ob::PlannerPtr(const ompl::base::SpaceInformationPtr &si, const std::string &name, const ModelBasedPlanningContextSpecification &spec)> ConfiguredPlannerAllocator
Definition: model_based_planning_context.h:89
ompl_interface::PlanningContextManager::getMaximumGoalSamples
unsigned int getMaximumGoalSamples() const
Definition: planning_context_manager.h:153
ompl_interface::MultiQueryPlannerAllocator::storage_
ob::PlannerDataStorage storage_
Definition: planning_context_manager.h:140
ompl_interface::MultiQueryPlannerAllocator::planner_data_storage_paths_
std::map< std::string, std::string > planner_data_storage_paths_
Definition: planning_context_manager.h:137
planning_interface::PlannerConfigurationSettings
ompl_interface::PlanningContextManager::setMaximumStateSamplingAttempts
void setMaximumStateSamplingAttempts(unsigned int max_state_sampling_attempts)
Definition: planning_context_manager.h:135
ompl_interface::PlanningContextManager::getMaximumStateSamplingAttempts
unsigned int getMaximumStateSamplingAttempts() const
Definition: planning_context_manager.h:129
ompl_interface::PlanningContextManager::registerDefaultPlanners
void registerDefaultPlanners()
Definition: planning_context_manager.cpp:275
ompl_interface::PlanningContextManager::minimum_waypoint_count_
unsigned int minimum_waypoint_count_
Definition: planning_context_manager.h:291
planning_scene
ompl_interface::PlanningContextManager::MOVEIT_STRUCT_FORWARD
MOVEIT_STRUCT_FORWARD(CachedContexts)
model_based_state_space_factory.h
ros::NodeHandle
ompl_interface::PlanningContextManager::registerPlannerAllocatorHelper
void registerPlannerAllocatorHelper(const std::string &planner_id)
Definition: planning_context_manager.cpp:267
ompl_interface::PlanningContextManager::setMaximumGoalSamples
void setMaximumGoalSamples(unsigned int max_goal_samples)
Definition: planning_context_manager.h:159


ompl
Author(s): Ioan Sucan
autogenerated on Fri May 3 2024 02:29:39