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 #pragma once
38 
43 #include <moveit_msgs/MotionPlanRequest.h>
44 #include <moveit_msgs/MotionPlanResponse.h>
45 #include <string>
46 #include <map>
47 #include <ros/ros.h>
48 
50 namespace ompl_interface
51 {
53 class OMPLInterface
54 {
55 public:
58  OMPLInterface(const moveit::core::RobotModelConstPtr& robot_model, const ros::NodeHandle& nh = ros::NodeHandle("~"));
59 
64  OMPLInterface(const moveit::core::RobotModelConstPtr& robot_model,
66  const ros::NodeHandle& nh = ros::NodeHandle("~"));
67 
68  virtual ~OMPLInterface();
69 
73 
77  {
79  }
80 
81  ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
82  const planning_interface::MotionPlanRequest& req) const;
83  ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
85  moveit_msgs::MoveItErrorCodes& error_code) const;
86 
88  {
89  return context_manager_;
90  }
91 
93  {
94  return context_manager_;
95  }
96 
98  {
100  }
101 
103  {
105  }
106 
107  void useConstraintsApproximations(bool flag)
108  {
110  }
111 
113  {
115  }
116  bool simplifySolutions() const
117  {
118  return simplify_solutions_;
119  }
120 
121  void simplifySolutions(bool flag)
122  {
123  simplify_solutions_ = flag;
124  }
125 
127  void printStatus();
128 
129 protected:
131  bool loadPlannerConfiguration(const std::string& group_name, const std::string& planner_id,
132  const std::map<std::string, std::string>& group_params,
134 
137 
139  void loadConstraintSamplers();
140 
141  void configureContext(const ModelBasedPlanningContextPtr& context) const;
142 
144  ModelBasedPlanningContextPtr prepareForSolve(const planning_interface::MotionPlanRequest& req,
145  const planning_scene::PlanningSceneConstPtr& planning_scene,
146  moveit_msgs::MoveItErrorCodes* error_code, unsigned int* attempts,
147  double* timeout) const;
148 
150 
152  moveit::core::RobotModelConstPtr robot_model_;
153 
154  constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_;
155 
157 
159 
160  bool simplify_solutions_;
161 
162 private:
163  constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr constraint_sampler_manager_loader_;
164 };
165 } // namespace ompl_interface
ompl_interface::OMPLInterface::getConstraintSamplerManager
constraint_samplers::ConstraintSamplerManager & getConstraintSamplerManager()
Definition: ompl_interface.h:161
ompl_interface::OMPLInterface::prepareForSolve
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.
ompl_interface::OMPLInterface::constraint_sampler_manager_
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
Definition: ompl_interface.h:218
ompl_interface::OMPLInterface::~OMPLInterface
virtual ~OMPLInterface()
constraint_samplers::ConstraintSamplerManager
ompl_interface::OMPLInterface::use_constraints_approximations_
bool use_constraints_approximations_
Definition: ompl_interface.h:222
ompl_interface::OMPLInterface::loadPlannerConfigurations
void loadPlannerConfigurations()
Configure the planners.
Definition: ompl_interface.cpp:170
ros.h
ompl_interface::OMPLInterface::loadConstraintSamplers
void loadConstraintSamplers()
Load the additional plugins for sampling constraints.
Definition: ompl_interface.cpp:123
ompl_interface::OMPLInterface::setPlannerConfigurations
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
Specify configurations for the planners.
Definition: ompl_interface.cpp:80
ompl_interface::OMPLInterface::printStatus
void printStatus()
Print the status of this node.
Definition: ompl_interface.cpp:285
ompl_interface::OMPLInterface::constraint_sampler_manager_loader_
constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr constraint_sampler_manager_loader_
Definition: ompl_interface.h:227
ompl_interface::OMPLInterface::simplifySolutions
bool simplifySolutions() const
Definition: ompl_interface.h:180
ompl_interface
The MoveIt interface to OMPL.
Definition: constrained_goal_sampler.h:46
planning_interface.h
ompl_interface::PlanningContextManager
Definition: planning_context_manager.h:111
ompl_interface::OMPLInterface::OMPLInterface
OMPLInterface(const moveit::core::RobotModelConstPtr &robot_model, const ros::NodeHandle &nh=ros::NodeHandle("~"))
Initialize OMPL-based planning for a particular robot model. ROS configuration is read from the speci...
Definition: ompl_interface.cpp:49
planning_interface::PlannerConfigurationMap
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
ompl_interface::PlanningContextManager::getPlannerConfigurations
const planning_interface::PlannerConfigurationMap & getPlannerConfigurations() const
Return the previously set planner configurations.
Definition: planning_context_manager.h:123
ompl_interface::OMPLInterface::getPlanningContextManager
const PlanningContextManager & getPlanningContextManager() const
Definition: ompl_interface.h:151
ompl_interface::OMPLInterface::configureContext
void configureContext(const ModelBasedPlanningContextPtr &context) const
Definition: ompl_interface.cpp:118
ompl_interface::OMPLInterface::nh_
ros::NodeHandle nh_
Definition: ompl_interface.h:213
ompl_interface::OMPLInterface::useConstraintsApproximations
void useConstraintsApproximations(bool flag)
Definition: ompl_interface.h:171
planning_interface::MotionPlanRequest
moveit_msgs::MotionPlanRequest MotionPlanRequest
planning_context_manager.h
constraint_sampler_manager_loader.h
constraint_sampler_manager.h
ompl_interface::OMPLInterface::context_manager_
PlanningContextManager context_manager_
Definition: ompl_interface.h:220
ompl_interface::OMPLInterface::getPlannerConfigurations
const planning_interface::PlannerConfigurationMap & getPlannerConfigurations() const
Get the configurations for the planners that are already loaded.
Definition: ompl_interface.h:140
ompl_interface::OMPLInterface::getPlanningContext
ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req) const
Definition: ompl_interface.cpp:99
ompl_interface::OMPLInterface::loadPlannerConfiguration
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.
Definition: ompl_interface.cpp:129
ompl_interface::OMPLInterface::robot_model_
moveit::core::RobotModelConstPtr robot_model_
The ROS node handle.
Definition: ompl_interface.h:216
ompl_interface::OMPLInterface::isUsingConstraintsApproximations
bool isUsingConstraintsApproximations() const
Definition: ompl_interface.h:176
planning_interface::PlannerConfigurationSettings
planning_scene
ompl_interface::OMPLInterface::simplify_solutions_
bool simplify_solutions_
Definition: ompl_interface.h:224
ros::NodeHandle


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