moveit2
The MoveIt Motion Planning Framework for ROS 2.
ompl_planner_manager.cpp
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, Dave Coleman */
36 
40 
41 #include <ompl/util/Console.h>
42 
43 namespace ompl_interface
44 {
45 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ompl_planning.ompl_planner_manager");
46 static const rclcpp::Logger OMPL_LOGGER = rclcpp::get_logger("ompl");
47 
49 {
50 public:
52  {
53  class OutputHandler : public ompl::msg::OutputHandler
54  {
55  public:
56  void log(const std::string& text, ompl::msg::LogLevel level, const char* filename, int line) override
57  {
58  switch (level)
59  {
60  case ompl::msg::LOG_DEV2:
61  case ompl::msg::LOG_DEV1:
62  case ompl::msg::LOG_DEBUG:
63  case ompl::msg::LOG_INFO:
64  // LOG_INFO too verbose for MoveIt usage, so we reduce the logger level to DEBUG
65  RCLCPP_DEBUG(OMPL_LOGGER, "%s:%i - %s", filename, line, text.c_str());
66  break;
67  case ompl::msg::LOG_WARN:
68  RCLCPP_WARN(OMPL_LOGGER, "%s:%i - %s", filename, line, text.c_str());
69  break;
70  case ompl::msg::LOG_ERROR:
71  RCLCPP_ERROR(OMPL_LOGGER, "%s:%i - %s", filename, line, text.c_str());
72  break;
73  case ompl::msg::LOG_NONE:
74  default:
75  /* ignore */
76  break;
77  }
78  }
79  };
80 
81  output_handler_ = std::make_shared<OutputHandler>();
82  ompl::msg::useOutputHandler(output_handler_.get());
83  }
84 
85  bool initialize(const moveit::core::RobotModelConstPtr& model, const rclcpp::Node::SharedPtr& node,
86  const std::string& parameter_namespace) override
87  {
88  ompl_interface_ = std::make_unique<OMPLInterface>(model, node, parameter_namespace);
89  setPlannerConfigurations(ompl_interface_->getPlannerConfigurations());
90  return true;
91  }
92 
94  {
95  return req.trajectory_constraints.constraints.empty();
96  }
97 
98  std::string getDescription() const override
99  {
100  return "OMPL";
101  }
102 
103  void getPlanningAlgorithms(std::vector<std::string>& algs) const override
104  {
105  const planning_interface::PlannerConfigurationMap& pconfig = ompl_interface_->getPlannerConfigurations();
106  algs.clear();
107  algs.reserve(pconfig.size());
108  for (const std::pair<const std::string, planning_interface::PlannerConfigurationSettings>& config : pconfig)
109  algs.push_back(config.first);
110  }
111 
113  {
114  // this call can add a few more configs than we pass in (adds defaults)
115  ompl_interface_->setPlannerConfigurations(pconfig);
116  // so we read the configs instead of just setting pconfig
117  PlannerManager::setPlannerConfigurations(ompl_interface_->getPlannerConfigurations());
118  }
119 
120  planning_interface::PlanningContextPtr
121  getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
123  moveit_msgs::msg::MoveItErrorCodes& error_code) const override
124  {
125  return ompl_interface_->getPlanningContext(planning_scene, req, error_code);
126  }
127 
128 private:
129  rclcpp::Node::SharedPtr node_;
130  std::unique_ptr<OMPLInterface> ompl_interface_;
131  std::shared_ptr<ompl::msg::OutputHandler> output_handler_;
132 };
133 
134 } // namespace ompl_interface
135 
136 #include <pluginlib/class_list_macros.hpp>
137 
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig) override
Specify the settings to be used for specific algorithms.
planning_interface::PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::msg::MoveItErrorCodes &error_code) const override
Construct a planning context given the current scene and a planning request. If a problem is encounte...
std::string getDescription() const override
Get.
bool canServiceRequest(const moveit_msgs::msg::MotionPlanRequest &req) const override
Determine whether this plugin instance is able to represent this planning request.
bool initialize(const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace) override
void getPlanningAlgorithms(std::vector< std::string > &algs) const override
Get the names of the known planning algorithms (values that can be filled as planner_id in the planni...
Base class for a MoveIt planner.
The MoveIt interface to OMPL.
This namespace includes the base class for MoveIt planners.
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.