moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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
43#include "cartesian_limits_parameters.hpp"
45
46#include <pluginlib/class_list_macros.hpp>
47
48#include <pluginlib/class_loader.hpp>
49
50#include <memory>
52
54{
55namespace
56{
57const std::string PARAM_NAMESPACE_LIMITS = "robot_description_planning";
58rclcpp::Logger getLogger()
59{
60 return moveit::getLogger("moveit.planners.pilz.command_planner");
61}
62} // namespace
63
64bool CommandPlanner::initialize(const moveit::core::RobotModelConstPtr& model, const rclcpp::Node::SharedPtr& node,
65 const std::string& ns)
66{
67 // Call parent class initialize
69
70 // Store the model and the namespace
71 model_ = model;
72 namespace_ = ns;
73
74 // Obtain the aggregated joint limits
76 node, PARAM_NAMESPACE_LIMITS, model->getActiveJointModels());
77
78 // Obtain cartesian limits
79 param_listener_ =
80 std::make_shared<cartesian_limits::ParamListener>(node, PARAM_NAMESPACE_LIMITS + ".cartesian_limits");
81 params_ = param_listener_->get_params();
82
83 // Load the planning context loader
84 planner_context_loader_ = std::make_unique<pluginlib::ClassLoader<PlanningContextLoader>>(
85 "pilz_industrial_motion_planner", "pilz_industrial_motion_planner::PlanningContextLoader");
86
87 // List available plugins
88 const std::vector<std::string>& factories = planner_context_loader_->getDeclaredClasses();
89 std::stringstream ss;
90 for (const auto& factory : factories)
91 {
92 ss << factory << ' ';
93 }
94
95 RCLCPP_INFO_STREAM(getLogger(), "Available plugins: " << ss.str());
96
97 // Load each factory
98 for (const auto& factory : factories)
99 {
100 RCLCPP_INFO_STREAM(getLogger(), "About to load: " << factory);
101 PlanningContextLoaderPtr loader_pointer(planner_context_loader_->createSharedInstance(factory));
102
104 limits.setJointLimits(aggregated_limit_active_joints_);
105 limits.setCartesianLimits(params_);
106
107 loader_pointer->setLimits(limits);
108 loader_pointer->setModel(model_);
109
110 registerContextLoader(loader_pointer);
111 }
112
113 return true;
114}
115
117{
118 return "Pilz Industrial Motion Planner";
119}
120
121void CommandPlanner::getPlanningAlgorithms(std::vector<std::string>& algs) const
122{
123 algs.clear();
124
125 for (const auto& context_loader : context_loader_map_)
126 {
127 algs.push_back(context_loader.first);
128 }
129}
130
131planning_interface::PlanningContextPtr
132CommandPlanner::getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
133 const moveit_msgs::msg::MotionPlanRequest& req,
134 moveit_msgs::msg::MoveItErrorCodes& error_code) const
135{
136 // TODO(henningkayser): print req
137 // RCLCPP_DEBUG_STREAM(getLogger(), "Loading PlanningContext for request\n<request>\n" << req << "\n</request>");
138 RCLCPP_DEBUG(getLogger(), "Loading PlanningContext");
139
140 // Check that a loaded for this request exists
141 if (!canServiceRequest(req))
142 {
143 RCLCPP_ERROR_STREAM(getLogger(), "No ContextLoader for planner_id '" << req.planner_id.c_str()
144 << "' found. Planning not possible.");
145 return nullptr;
146 }
147
148 planning_interface::PlanningContextPtr planning_context;
149
150 if (context_loader_map_.at(req.planner_id)->loadContext(planning_context, req.planner_id, req.group_name))
151 {
152 RCLCPP_DEBUG_STREAM(getLogger(),
153 "Found planning context loader for " << req.planner_id << " group:" << req.group_name);
154 planning_context->setMotionPlanRequest(req);
155 planning_context->setPlanningScene(planning_scene);
156 return planning_context;
157 }
158 else
159 {
160 error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
161 return nullptr;
162 }
163}
164
165bool CommandPlanner::canServiceRequest(const moveit_msgs::msg::MotionPlanRequest& req) const
166{
167 if (context_loader_map_.find(req.planner_id) == context_loader_map_.end())
168 {
169 RCLCPP_ERROR(getLogger(), "Cannot service planning request because planner ID '%s' does not exist.",
170 req.planner_id.c_str());
171 return false;
172 }
173
174 if (req.group_name.empty())
175 {
176 RCLCPP_ERROR(getLogger(), "Cannot service planning request because group name is not specified.");
177 return false;
178 }
179
180 auto joint_mode_group_ptr = model_->getJointModelGroup(req.group_name);
181 if (joint_mode_group_ptr == nullptr)
182 {
183 RCLCPP_ERROR(getLogger(), "Cannot service planning request because group '%s' does not exist.",
184 req.group_name.c_str());
185 return false;
186 }
187
188 if (joint_mode_group_ptr->getSolverInstance() == nullptr)
189 {
190 RCLCPP_ERROR(getLogger(), "Cannot service planning request because group '%s' does have an IK solver instance.",
191 req.group_name.c_str());
192 return false;
193 }
194
195 if (!req.trajectory_constraints.constraints.empty())
196 {
197 RCLCPP_ERROR(getLogger(),
198 "Cannot service planning request because PILZ does not support 'trajectory constraints'.");
199 return false;
200 }
201
202 return true;
203}
204
207{
208 // Only add if command is not already in list, throw exception if not
209 if (context_loader_map_.find(planning_context_loader->getAlgorithm()) == context_loader_map_.end())
210 {
211 context_loader_map_[planning_context_loader->getAlgorithm()] = planning_context_loader;
212 RCLCPP_INFO_STREAM(getLogger(), "Registered Algorithm [" << planning_context_loader->getAlgorithm() << ']');
213 }
214 else
215 {
216 throw ContextLoaderRegistrationException("The command [" + planning_context_loader->getAlgorithm() +
217 "] is already registered");
218 }
219}
220
221} // namespace pilz_industrial_motion_planner
222
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
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.
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(cartesian_limits::Params &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)
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
std::shared_ptr< PlanningContextLoader > PlanningContextLoaderPtr
This namespace includes the central class for representing planning contexts.
const std::string PARAM_NAMESPACE_LIMITS