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 #include <moveit/utils/logger.hpp>
41 
42 #include <ompl/util/Console.h>
43 
44 namespace ompl_interface
45 {
46 namespace
47 {
48 rclcpp::Logger getLogger()
49 {
50  return moveit::getLogger("ompl_planner_manager");
51 }
52 } // namespace
53 
55 {
56 public:
58  {
59  class OutputHandler : public ompl::msg::OutputHandler
60  {
61  public:
62  void log(const std::string& text, ompl::msg::LogLevel level, const char* filename, int line) override
63  {
64  switch (level)
65  {
66  case ompl::msg::LOG_DEV2:
67  case ompl::msg::LOG_DEV1:
68  case ompl::msg::LOG_DEBUG:
69  case ompl::msg::LOG_INFO:
70  // LOG_INFO too verbose for MoveIt usage, so we reduce the logger level to DEBUG
71  RCLCPP_DEBUG(getLogger(), "%s:%i - %s", filename, line, text.c_str());
72  break;
73  case ompl::msg::LOG_WARN:
74  RCLCPP_WARN(getLogger(), "%s:%i - %s", filename, line, text.c_str());
75  break;
76  case ompl::msg::LOG_ERROR:
77  RCLCPP_ERROR(getLogger(), "%s:%i - %s", filename, line, text.c_str());
78  break;
79  case ompl::msg::LOG_NONE:
80  default:
81  /* ignore */
82  break;
83  }
84  }
85  };
86 
87  output_handler_ = std::make_shared<OutputHandler>();
88  ompl::msg::useOutputHandler(output_handler_.get());
89  }
90 
91  bool initialize(const moveit::core::RobotModelConstPtr& model, const rclcpp::Node::SharedPtr& node,
92  const std::string& parameter_namespace) override
93  {
94  ompl_interface_ = std::make_unique<OMPLInterface>(model, node, parameter_namespace);
95  setPlannerConfigurations(ompl_interface_->getPlannerConfigurations());
96  return true;
97  }
98 
100  {
101  return req.trajectory_constraints.constraints.empty();
102  }
103 
104  std::string getDescription() const override
105  {
106  return "OMPL";
107  }
108 
109  void getPlanningAlgorithms(std::vector<std::string>& algs) const override
110  {
111  const planning_interface::PlannerConfigurationMap& pconfig = ompl_interface_->getPlannerConfigurations();
112  algs.clear();
113  algs.reserve(pconfig.size());
114  for (const std::pair<const std::string, planning_interface::PlannerConfigurationSettings>& config : pconfig)
115  algs.push_back(config.first);
116  }
117 
119  {
120  // this call can add a few more configs than we pass in (adds defaults)
121  ompl_interface_->setPlannerConfigurations(pconfig);
122  // so we read the configs instead of just setting pconfig
123  PlannerManager::setPlannerConfigurations(ompl_interface_->getPlannerConfigurations());
124  }
125 
126  planning_interface::PlanningContextPtr
127  getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
129  moveit_msgs::msg::MoveItErrorCodes& error_code) const override
130  {
131  return ompl_interface_->getPlanningContext(planning_scene, req, error_code);
132  }
133 
134 private:
135  rclcpp::Node::SharedPtr node_;
136  std::unique_ptr<OMPLInterface> ompl_interface_;
137  std::shared_ptr<ompl::msg::OutputHandler> output_handler_;
138 };
139 
140 } // namespace ompl_interface
141 
142 #include <pluginlib/class_list_macros.hpp>
143 
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 a short string that identifies the planning interface.
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.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
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.