ompl_interface.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2011, 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_OMPL_INTERFACE_
38 #define MOVEIT_OMPL_INTERFACE_OMPL_INTERFACE_
39 
45 #include <moveit_msgs/MotionPlanRequest.h>
46 #include <moveit_msgs/MotionPlanResponse.h>
47 #include <string>
48 #include <map>
49 #include <ros/ros.h>
50 
52 namespace ompl_interface
53 {
57 {
58 public:
61  OMPLInterface(const robot_model::RobotModelConstPtr& kmodel, const ros::NodeHandle& nh = ros::NodeHandle("~"));
62 
67  OMPLInterface(const robot_model::RobotModelConstPtr& kmodel,
69  const ros::NodeHandle& nh = ros::NodeHandle("~"));
70 
71  virtual ~OMPLInterface();
72 
76 
80  {
82  }
83 
84  ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
85  const planning_interface::MotionPlanRequest& req) const;
86  ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
88  moveit_msgs::MoveItErrorCodes& error_code) const;
89 
90  ModelBasedPlanningContextPtr getPlanningContext(const std::string& config,
91  const std::string& factory_type = "") const;
92 
93  ModelBasedPlanningContextPtr getLastPlanningContext() const
94  {
96  }
97 
99  {
100  return context_manager_;
101  }
102 
104  {
105  return context_manager_;
106  }
107 
109  {
110  return *constraints_library_;
111  }
112 
114  {
115  return *constraints_library_;
116  }
117 
119  {
121  }
122 
124  {
126  }
127 
129  {
131  }
132 
134  {
136  }
137 
138  void loadConstraintApproximations(const std::string& path);
139 
140  void saveConstraintApproximations(const std::string& path);
141 
142  bool simplifySolutions() const
143  {
144  return simplify_solutions_;
145  }
146 
147  void simplifySolutions(bool flag)
148  {
149  simplify_solutions_ = flag;
150  }
151 
155 
159 
161  void printStatus();
162 
163 protected:
165  bool loadPlannerConfiguration(const std::string& group_name, const std::string& planner_id,
166  const std::map<std::string, std::string>& group_params,
168 
171 
173  void loadConstraintSamplers();
174 
175  void configureContext(const ModelBasedPlanningContextPtr& context) const;
176 
178  ModelBasedPlanningContextPtr prepareForSolve(const planning_interface::MotionPlanRequest& req,
179  const planning_scene::PlanningSceneConstPtr& planning_scene,
180  moveit_msgs::MoveItErrorCodes* error_code, unsigned int* attempts,
181  double* timeout) const;
182 
184 
186  robot_model::RobotModelConstPtr kmodel_;
187 
188  constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_;
189 
191 
192  ConstraintsLibraryPtr constraints_library_;
194 
196 
197 private:
198  constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr constraint_sampler_manager_loader_;
199 };
200 }
201 
202 #endif
PlanningContextManager & getPlanningContextManager()
bool loadPlannerConfiguration(const std::string &group_name, const std::string &planner_id, const std::map< std::string, std::string > &group_params, planning_interface::PlannerConfigurationSettings &planner_config)
Load planner configurations for specified group into planner_config.
const planning_interface::PlannerConfigurationMap & getPlannerConfigurations() const
Get the configurations for the planners that are already loaded.
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr constraint_sampler_manager_loader_
ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req) const
void configureContext(const ModelBasedPlanningContextPtr &context) const
constraint_samplers::ConstraintSamplerManager & getConstraintSamplerManager()
bool loadConstraintApproximations()
Look up param server &#39;constraint_approximations&#39; and use its value as the path to load constraint app...
The MoveIt! interface to OMPL.
void loadPlannerConfigurations()
Configure the planners.
robot_model::RobotModelConstPtr kmodel_
The ROS node handle.
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
Specify configurations for the planners.
bool isUsingConstraintsApproximations() const
void useConstraintsApproximations(bool flag)
const PlanningContextManager & getPlanningContextManager() const
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
ConstraintsLibraryPtr constraints_library_
PlanningContextManager context_manager_
void printStatus()
Print the status of this node.
const planning_interface::PlannerConfigurationMap & getPlannerConfigurations() const
Return the previously set planner configurations.
const ConstraintsLibrary & getConstraintsLibrary() const
void loadConstraintSamplers()
Load the additional plugins for sampling constraints.
OMPLInterface(const robot_model::RobotModelConstPtr &kmodel, const ros::NodeHandle &nh=ros::NodeHandle("~"))
Initialize OMPL-based planning for a particular robot model. ROS configuration is read from the speci...
const constraint_samplers::ConstraintSamplerManager & getConstraintSamplerManager() const
moveit_msgs::MotionPlanRequest MotionPlanRequest
ModelBasedPlanningContextPtr prepareForSolve(const planning_interface::MotionPlanRequest &req, const planning_scene::PlanningSceneConstPtr &planning_scene, moveit_msgs::MoveItErrorCodes *error_code, unsigned int *attempts, double *timeout) const
Configure the OMPL planning context for a new planning request.
ModelBasedPlanningContextPtr getLastPlanningContext() const
bool saveConstraintApproximations()
Look up param server &#39;constraint_approximations&#39; and use its value as the path to save constraint app...
ConstraintsLibrary & getConstraintsLibrary()
ModelBasedPlanningContextPtr getLastPlanningContext() const


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