moveit2
The MoveIt Motion Planning Framework for ROS 2.
chomp_plugin.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 
40 
41 #include <pluginlib/class_list_macros.hpp>
42 #include <vector>
43 
44 namespace chomp_interface
45 {
46 static const rclcpp::Logger LOGGER = rclcpp::get_logger("chomp_optimizer");
47 
49 {
50 public:
52  {
53  }
54 
55  bool initialize(const moveit::core::RobotModelConstPtr& model, const rclcpp::Node::SharedPtr& node,
56  const std::string& /* unused */) override
57  {
59  for (const std::string& group : model->getJointModelGroupNames())
60  {
61  planning_contexts_[group] = std::make_shared<CHOMPPlanningContext>("chomp_planning_context", group, model, node);
62  const planning_interface::PlannerConfigurationSettings planner_config_settings{
63  group, group, std::map<std::string, std::string>()
64  };
65  pconfig[planner_config_settings.name] = planner_config_settings;
66  }
67 
68  setPlannerConfigurations(pconfig);
69  return true;
70  }
71 
72  planning_interface::PlanningContextPtr
73  getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
75  moveit_msgs::msg::MoveItErrorCodes& error_code) const override
76  {
77  error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
78 
79  if (req.group_name.empty())
80  {
81  RCLCPP_ERROR(LOGGER, "No group specified to plan for");
82  error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME;
83  return planning_interface::PlanningContextPtr();
84  }
85 
86  if (!planning_scene)
87  {
88  RCLCPP_ERROR(LOGGER, "No planning scene supplied as input");
89  error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
90  return planning_interface::PlanningContextPtr();
91  }
92 
93  // create PlanningScene using hybrid collision detector
94  planning_scene::PlanningScenePtr ps = planning_scene->diff();
96 
97  // retrieve and configure existing context
98  const CHOMPPlanningContextPtr& context = planning_contexts_.at(req.group_name);
99  context->setPlanningScene(ps);
100  context->setMotionPlanRequest(req);
101  error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
102  return context;
103  }
104 
105  bool canServiceRequest(const planning_interface::MotionPlanRequest& /*req*/) const override
106  {
107  // TODO: this is a dummy implementation
108  // capabilities.dummy = false;
109  return true;
110  }
111 
112  std::string getDescription() const override
113  {
114  return "CHOMP";
115  }
116 
117  void getPlanningAlgorithms(std::vector<std::string>& algs) const override
118  {
119  algs.resize(1);
120  algs[0] = "CHOMP";
121  }
122 
124  {
125  config_settings_ = pcs;
126  }
127 
128 protected:
129  std::map<std::string, CHOMPPlanningContextPtr> planning_contexts_;
130 };
131 
132 } // namespace chomp_interface
133 
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
std::string getDescription() const override
Get.
bool canServiceRequest(const planning_interface::MotionPlanRequest &) const override
Determine whether this plugin instance is able to represent this planning request.
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pcs) override
Specify the settings to be used for specific algorithms.
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...
std::map< std::string, CHOMPPlanningContextPtr > planning_contexts_
bool initialize(const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string &) override
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...
Base class for a MoveIt planner.
PlannerConfigurationMap config_settings_
All the existing planning configurations. The name of the configuration is the key of the map....
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.
Specify the settings for a particular planning algorithm, for a particular group. The Planner plugin ...