moveit2
The MoveIt Motion Planning Framework for ROS 2.
pilz_industrial_motion_planner.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018 Pilz GmbH & Co. KG
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 Pilz GmbH & Co. KG 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 #include <rclcpp/logging.hpp>
36 
38 
42 
45 
46 #include <pluginlib/class_list_macros.hpp>
47 
48 #include <pluginlib/class_loader.hpp>
49 
50 #include <memory>
51 
53 {
54 static const std::string PARAM_NAMESPACE_LIMITS = "robot_description_planning";
55 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.pilz_industrial_motion_planner");
56 
57 bool CommandPlanner::initialize(const moveit::core::RobotModelConstPtr& model, const rclcpp::Node::SharedPtr& node,
58  const std::string& ns)
59 {
60  // Call parent class initialize
62 
63  // Store the model and the namespace
64  model_ = model;
65  namespace_ = ns;
66 
67  // Obtain the aggregated joint limits
69  node, PARAM_NAMESPACE_LIMITS, model->getActiveJointModels());
70 
71  // Obtain cartesian limits
72  cartesian_limit_ =
74 
75  // Load the planning context loader
76  planner_context_loader = std::make_unique<pluginlib::ClassLoader<PlanningContextLoader>>(
77  "pilz_industrial_motion_planner", "pilz_industrial_motion_planner::PlanningContextLoader");
78 
79  // List available plugins
80  const std::vector<std::string>& factories = planner_context_loader->getDeclaredClasses();
81  std::stringstream ss;
82  for (const auto& factory : factories)
83  {
84  ss << factory << " ";
85  }
86 
87  RCLCPP_INFO_STREAM(LOGGER, "Available plugins: " << ss.str());
88 
89  // Load each factory
90  for (const auto& factory : factories)
91  {
92  RCLCPP_INFO_STREAM(LOGGER, "About to load: " << factory);
93  PlanningContextLoaderPtr loader_pointer(planner_context_loader->createSharedInstance(factory));
94 
96  limits.setJointLimits(aggregated_limit_active_joints_);
97  limits.setCartesianLimits(cartesian_limit_);
98 
99  loader_pointer->setLimits(limits);
100  loader_pointer->setModel(model_);
101 
102  registerContextLoader(loader_pointer);
103  }
104 
105  // Specify for which joint model groups this planner is usable
107 
108  for (const auto& group : model_->getJointModelGroupNames())
109  {
110  const planning_interface::PlannerConfigurationSettings planner_config_settings{
111  group, group, std::map<std::string, std::string>()
112  };
113  pconfig[planner_config_settings.name] = planner_config_settings;
114  }
115 
116  setPlannerConfigurations(pconfig);
117 
118  return true;
119 }
120 
122 {
123  return "Pilz Industrial Motion Planner";
124 }
125 
126 void CommandPlanner::getPlanningAlgorithms(std::vector<std::string>& algs) const
127 {
128  algs.clear();
129 
130  for (const auto& context_loader : context_loader_map_)
131  {
132  algs.push_back(context_loader.first);
133  }
134 }
135 
136 planning_interface::PlanningContextPtr
137 CommandPlanner::getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
139  moveit_msgs::msg::MoveItErrorCodes& error_code) const
140 {
141  // TODO(henningkayser): print req
142  // RCLCPP_DEBUG_STREAM(LOGGER, "Loading PlanningContext for request\n<request>\n" << req << "\n</request>");
143  RCLCPP_DEBUG(LOGGER, "Loading PlanningContext");
144 
145  // Check that a loaded for this request exists
146  if (!canServiceRequest(req))
147  {
148  RCLCPP_ERROR_STREAM(LOGGER, "No ContextLoader for planner_id '" << req.planner_id.c_str()
149  << "' found. Planning not possible.");
150  return nullptr;
151  }
152 
153  planning_interface::PlanningContextPtr planning_context;
154 
155  if (context_loader_map_.at(req.planner_id)->loadContext(planning_context, req.planner_id, req.group_name))
156  {
157  RCLCPP_DEBUG_STREAM(LOGGER, "Found planning context loader for " << req.planner_id << " group:" << req.group_name);
158  planning_context->setMotionPlanRequest(req);
159  planning_context->setPlanningScene(planning_scene);
160  return planning_context;
161  }
162  else
163  {
164  error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
165  return nullptr;
166  }
167 }
168 
170 {
171  return context_loader_map_.find(req.planner_id) != context_loader_map_.end();
172 }
173 
175  const pilz_industrial_motion_planner::PlanningContextLoaderPtr& planning_context_loader)
176 {
177  // Only add if command is not already in list, throw exception if not
178  if (context_loader_map_.find(planning_context_loader->getAlgorithm()) == context_loader_map_.end())
179  {
180  context_loader_map_[planning_context_loader->getAlgorithm()] = planning_context_loader;
181  RCLCPP_INFO_STREAM(LOGGER, "Registered Algorithm [" << planning_context_loader->getAlgorithm() << "]");
182  }
183  else
184  {
185  throw ContextLoaderRegistrationException("The command [" + planning_context_loader->getAlgorithm() +
186  "] is already registered");
187  }
188 }
189 
191 {
192  config_settings_ = pcs;
193 }
194 
195 } // namespace pilz_industrial_motion_planner
196 
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
static CartesianLimit getAggregatedLimits(const rclcpp::Node::SharedPtr &node, const std::string &param_namespace)
Loads cartesian limits from the node parameters.
MoveIt Plugin for Planning with Standard Robot Commands This planner is dedicated to return a instanc...
bool canServiceRequest(const planning_interface::MotionPlanRequest &req) const override
Checks if the request can be handled.
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pcs) override
Specify the settings to be used for an algorithms.
planning_interface::PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::msg::MoveItErrorCodes &error_code) const override
Returns a PlanningContext that can be used to solve(calculate) the trajectory that corresponds to com...
void getPlanningAlgorithms(std::vector< std::string > &algs) const override
Returns the available planning commands.
bool initialize(const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string &ns) override
Initializes the planner Upon initialization this planner will look for plugins implementing pilz_indu...
void registerContextLoader(const pilz_industrial_motion_planner::PlanningContextLoaderPtr &planning_context_loader)
Register a PlanningContextLoader to be used by the CommandPlanner.
std::string getDescription() const override
Description of the planner.
static JointLimitsContainer getAggregatedLimits(const rclcpp::Node::SharedPtr &node, const std::string &param_namespace, const std::vector< const moveit::core::JointModel * > &joint_models)
Aggregates(combines) the joint limits from joint model and node parameters. The rules for the combina...
This class combines CartesianLimit and JointLimits into on single class.
void setCartesianLimits(CartesianLimit &cartesian_limit)
Set cartesian limits.
void setJointLimits(JointLimitsContainer &joint_limits)
Set joint limits.
Base class for a MoveIt planner.
virtual bool initialize(const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace)
PlannerConfigurationMap config_settings_
All the existing planning configurations. The name of the configuration is the key of the map....
std::shared_ptr< PlanningContextLoader > PlanningContextLoaderPtr
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 ...