moveit2
The MoveIt Motion Planning Framework for ROS 2.
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/msg/motion_plan_request.hpp>
44 #include <moveit_msgs/msg/motion_plan_response.hpp>
45 #include <rclcpp/node.hpp>
46 #include <string>
47 #include <map>
48 
50 namespace ompl_interface
51 {
55 {
56 public:
59  OMPLInterface(const moveit::core::RobotModelConstPtr& robot_model, const rclcpp::Node::SharedPtr& node,
60  const std::string& parameter_namespace);
61 
66  OMPLInterface(const moveit::core::RobotModelConstPtr& robot_model,
67  const planning_interface::PlannerConfigurationMap& pconfig, const rclcpp::Node::SharedPtr& node,
68  const std::string& parameter_namespace);
69 
70  virtual ~OMPLInterface();
71 
75 
79  {
81  }
82 
83  ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
84  const planning_interface::MotionPlanRequest& req) const;
85  ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
87  moveit_msgs::msg::MoveItErrorCodes& error_code) const;
88 
90  {
91  return context_manager_;
92  }
93 
95  {
96  return context_manager_;
97  }
98 
100  {
102  }
103 
105  {
107  }
108 
110  {
112  }
113 
115  {
117  }
118 
120  void printStatus();
121 
122 protected:
124  bool loadPlannerConfiguration(const std::string& group_name, const std::string& planner_id,
125  const std::map<std::string, std::string>& group_params,
127 
130 
132  void loadConstraintSamplers();
133 
135  ModelBasedPlanningContextPtr prepareForSolve(const planning_interface::MotionPlanRequest& req,
136  const planning_scene::PlanningSceneConstPtr& planning_scene,
137  moveit_msgs::msg::MoveItErrorCodes* error_code, unsigned int* attempts,
138  double* timeout) const;
139 
140  rclcpp::Node::SharedPtr node_;
141  const std::string parameter_namespace_;
142 
144  moveit::core::RobotModelConstPtr robot_model_;
145 
146  constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_;
147 
149 
151 
152 private:
153  constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr constraint_sampler_manager_loader_;
154 };
155 } // namespace ompl_interface
This class assists in the generation of a ConstraintSampler for a particular group from a moveit_msgs...
rclcpp::Node::SharedPtr node_
void printStatus()
Print the status of this node.
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
const PlanningContextManager & getPlanningContextManager() const
constraint_samplers::ConstraintSamplerManager & getConstraintSamplerManager()
const constraint_samplers::ConstraintSamplerManager & getConstraintSamplerManager() const
void loadConstraintSamplers()
Load the additional plugins for sampling constraints.
void useConstraintsApproximations(bool flag)
PlanningContextManager & getPlanningContextManager()
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
Specify configurations for the planners.
PlanningContextManager context_manager_
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.
bool isUsingConstraintsApproximations() const
moveit::core::RobotModelConstPtr robot_model_
The kinematic model for which motion plans are computed.
const std::string parameter_namespace_
The ROS node.
const planning_interface::PlannerConfigurationMap & getPlannerConfigurations() const
Get the configurations for the planners that are already loaded.
ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req) const
void loadPlannerConfigurations()
Configure the planners.
ModelBasedPlanningContextPtr prepareForSolve(const planning_interface::MotionPlanRequest &req, const planning_scene::PlanningSceneConstPtr &planning_scene, moveit_msgs::msg::MoveItErrorCodes *error_code, unsigned int *attempts, double *timeout) const
Configure the OMPL planning context for a new planning request.
OMPLInterface(const moveit::core::RobotModelConstPtr &robot_model, const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace)
Initialize OMPL-based planning for a particular robot model. ROS configuration is read from the speci...
const planning_interface::PlannerConfigurationMap & getPlannerConfigurations() const
Return the previously set planner configurations.
The MoveIt interface to OMPL.
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
Map from PlannerConfigurationSettings.name to PlannerConfigurationSettings.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
Specify the settings for a particular planning algorithm, for a particular group. The Planner plugin ...