moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
robot_model_loader.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, 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, E. Gil Jones */
36
38#include <rclcpp/clock.hpp>
39#include <rclcpp/duration.hpp>
40#include <rclcpp/logger.hpp>
41#include <rclcpp/logging.hpp>
42#include <rclcpp/parameter_value.hpp>
43#include <rclcpp/time.hpp>
44#include <typeinfo>
46
47namespace robot_model_loader
48{
49
50RobotModelLoader::RobotModelLoader(const rclcpp::Node::SharedPtr& node, const std::string& robot_description,
51 bool load_kinematics_solvers)
52 : node_(node), logger_(moveit::getLogger("moveit.ros.robot_model_loader"))
53{
54 Options opt(robot_description);
55 opt.load_kinematics_solvers = load_kinematics_solvers;
56 configure(opt);
57}
58
59RobotModelLoader::RobotModelLoader(const rclcpp::Node::SharedPtr& node, const Options& opt)
60 : node_(node), logger_(moveit::getLogger("moveit.ros.robot_model_loader"))
61{
62 configure(opt);
63}
64
66{
67 // Make sure we destroy the robot model first. It contains the loaded
68 // kinematics plugins, and those must be destroyed before the pluginlib class
69 // that implements them is destroyed (that happens when kinematics_loader_ is
70 // destroyed below). This is a workaround - ideally pluginlib would handle
71 // this better.
72 model_.reset();
73 rdf_loader_.reset();
74 kinematics_loader_.reset();
75}
76
77namespace
78{
79bool canSpecifyPosition(const moveit::core::JointModel* jmodel, const unsigned int index, const rclcpp::Logger& logger)
80{
81 bool ok = false;
82 if (jmodel->getType() == moveit::core::JointModel::PLANAR && index == 2)
83 {
84 RCLCPP_ERROR(logger, "Cannot specify position limits for orientation of planar joint '%s'",
85 jmodel->getName().c_str());
86 }
87 else if (jmodel->getType() == moveit::core::JointModel::FLOATING && index > 2)
88 {
89 RCLCPP_ERROR(logger, "Cannot specify position limits for orientation of floating joint '%s'",
90 jmodel->getName().c_str());
91 }
92 else if (jmodel->getType() == moveit::core::JointModel::REVOLUTE &&
93 static_cast<const moveit::core::RevoluteJointModel*>(jmodel)->isContinuous())
94 {
95 RCLCPP_ERROR(logger, "Cannot specify position limits for continuous joint '%s'", jmodel->getName().c_str());
96 }
97 else
98 {
99 ok = true;
100 }
101 return ok;
102}
103} // namespace
104
105void RobotModelLoader::configure(const Options& opt)
106{
107 rclcpp::Clock clock;
108 rclcpp::Time start = clock.now();
109 if (!opt.urdf_string_.empty() && !opt.srdf_string.empty())
110 {
111 rdf_loader_ = std::make_shared<rdf_loader::RDFLoader>(opt.urdf_string_, opt.srdf_string);
112 }
113 else
114 {
115 rdf_loader_ = std::make_shared<rdf_loader::RDFLoader>(node_, opt.robot_description);
116 }
117 if (rdf_loader_->getURDF())
118 {
119 const srdf::ModelSharedPtr& srdf =
120 rdf_loader_->getSRDF() ? rdf_loader_->getSRDF() : std::make_shared<srdf::Model>();
121 model_ = std::make_shared<moveit::core::RobotModel>(rdf_loader_->getURDF(), srdf);
122 }
123
124 if (model_ && !rdf_loader_->getRobotDescription().empty())
125 {
126 // if there are additional joint limits specified in some .yaml file, read those in
127 for (moveit::core::JointModel* joint_model : model_->getJointModels())
128 {
129 std::vector<moveit_msgs::msg::JointLimits> joint_limit = joint_model->getVariableBoundsMsg();
130 for (std::size_t joint_id = 0; joint_id < joint_limit.size(); ++joint_id)
131 {
132 std::string prefix =
133 rdf_loader_->getRobotDescription() + "_planning.joint_limits." + joint_limit[joint_id].joint_name + ".";
134
135 std::string param_name;
136 try
137 {
138 param_name = prefix + "max_position";
139 if (!node_->has_parameter(param_name))
140 {
141 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_DOUBLE);
142 }
143 double max_position;
144 if (node_->get_parameter(param_name, max_position))
145 {
146 if (canSpecifyPosition(joint_model, joint_id, logger_))
147 {
148 joint_limit[joint_id].has_position_limits = true;
149 joint_limit[joint_id].max_position = max_position;
150 }
151 }
152
153 param_name = prefix + "min_position";
154 if (!node_->has_parameter(param_name))
155 {
156 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_DOUBLE);
157 }
158 double min_position;
159 if (node_->get_parameter(param_name, min_position))
160 {
161 if (canSpecifyPosition(joint_model, joint_id, logger_))
162 {
163 joint_limit[joint_id].has_position_limits = true;
164 joint_limit[joint_id].min_position = min_position;
165 }
166 }
167
168 // Check if parameter has been declared to avoid exception
169 param_name = prefix + "has_velocity_limits";
170 if (!node_->has_parameter(param_name))
171 {
172 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_BOOL);
173 }
174 bool has_vel_limits = false;
175 if (node_->get_parameter(param_name, has_vel_limits))
176 joint_limit[joint_id].has_velocity_limits = has_vel_limits;
177
178 param_name = prefix + "has_acceleration_limits";
179 if (!node_->has_parameter(param_name))
180 {
181 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_BOOL);
182 }
183 bool has_acc_limits = false;
184 if (node_->get_parameter(param_name, has_acc_limits))
185 joint_limit[joint_id].has_acceleration_limits = has_acc_limits;
186
187 param_name = prefix + "has_jerk_limits";
188 if (!node_->has_parameter(param_name))
189 {
190 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_BOOL);
191 }
192 bool has_jerk_limits = false;
193 if (node_->get_parameter(param_name, has_jerk_limits))
194 joint_limit[joint_id].has_jerk_limits = has_jerk_limits;
195
196 if (has_vel_limits)
197 {
198 param_name = prefix + "max_velocity";
199 if (!node_->has_parameter(param_name))
200 {
201 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_DOUBLE);
202 }
203
204 if (!node_->get_parameter(param_name, joint_limit[joint_id].max_velocity))
205 {
206 RCLCPP_ERROR(logger_, "Specified a velocity limit for joint: %s but did not set a max velocity",
207 joint_limit[joint_id].joint_name.c_str());
208 }
209 }
210
211 if (has_acc_limits)
212 {
213 param_name = prefix + "max_acceleration";
214 if (!node_->has_parameter(param_name))
215 {
216 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_DOUBLE);
217 }
218
219 if (!node_->get_parameter(param_name, joint_limit[joint_id].max_acceleration))
220 {
221 RCLCPP_ERROR(logger_, "Specified an acceleration limit for joint: %s but did not set a max acceleration",
222 joint_limit[joint_id].joint_name.c_str());
223 }
224 }
225
226 if (has_jerk_limits)
227 {
228 param_name = prefix + "max_jerk";
229 if (!node_->has_parameter(param_name))
230 {
231 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_DOUBLE);
232 }
233
234 if (!node_->get_parameter(param_name, joint_limit[joint_id].max_jerk))
235 {
236 RCLCPP_ERROR(logger_, "Specified a jerk limit for joint: %s but did not set a max jerk",
237 joint_limit[joint_id].joint_name.c_str());
238 }
239 }
240 }
241 catch (const rclcpp::ParameterTypeException& e)
242 {
243 RCLCPP_ERROR_STREAM(logger_, "When getting the parameter " << param_name.c_str() << ": " << e.what());
244 }
245 }
246 joint_model->setVariableBounds(joint_limit);
247 }
248 }
249
250 if (model_ && opt.load_kinematics_solvers)
252
253 RCLCPP_DEBUG(logger_, "Loaded kinematic model in %f seconds", (clock.now() - start).seconds());
254}
255
256void RobotModelLoader::loadKinematicsSolvers(const kinematics_plugin_loader::KinematicsPluginLoaderPtr& kloader)
257{
258 if (rdf_loader_ && model_)
259 {
260 // load the kinematics solvers
261 if (kloader)
262 {
263 kinematics_loader_ = kloader;
264 }
265 else
266 {
267 kinematics_loader_ =
268 std::make_shared<kinematics_plugin_loader::KinematicsPluginLoader>(node_, rdf_loader_->getRobotDescription());
269 }
270 moveit::core::SolverAllocatorFn kinematics_allocator =
271 kinematics_loader_->getLoaderFunction(rdf_loader_->getSRDF());
272 const std::vector<std::string>& groups = kinematics_loader_->getKnownGroups();
273 std::stringstream ss;
274 std::copy(groups.begin(), groups.end(), std::ostream_iterator<std::string>(ss, " "));
275 RCLCPP_DEBUG(logger_, "Loaded information about the following groups: '%s' ", ss.str().c_str());
276 if (groups.empty() && !model_->getJointModelGroups().empty())
277 RCLCPP_WARN(logger_, "No kinematics plugins defined. Fill and load kinematics.yaml!");
278
279 std::map<std::string, moveit::core::SolverAllocatorFn> imap;
280 for (const std::string& group : groups)
281 {
282 // Check if a group in kinematics.yaml exists in the srdf
283 if (!model_->hasJointModelGroup(group))
284 continue;
285
286 const moveit::core::JointModelGroup* jmg = model_->getJointModelGroup(group);
287
288 kinematics::KinematicsBasePtr solver = kinematics_allocator(jmg);
289 if (solver)
290 {
291 std::string error_msg;
292 if (solver->supportsGroup(jmg, &error_msg))
293 {
294 imap[group] = kinematics_allocator;
295 }
296 else
297 {
298 const auto& s = *solver; // avoid clang-tidy's -Wpotentially-evaluated-expression
299 RCLCPP_ERROR(logger_, "Kinematics solver %s does not support joint group %s. Error: %s", typeid(s).name(),
300 group.c_str(), error_msg.c_str());
301 }
302 }
303 else
304 {
305 RCLCPP_ERROR(logger_, "Kinematics solver could not be instantiated for joint group %s.", group.c_str());
306 }
307 }
308 model_->setKinematicsAllocators(imap);
309
310 // set the default IK timeouts
311 const std::map<std::string, double>& timeout = kinematics_loader_->getIKTimeout();
312 for (const std::pair<const std::string, double>& it : timeout)
313 {
314 if (!model_->hasJointModelGroup(it.first))
315 continue;
316 moveit::core::JointModelGroup* jmg = model_->getJointModelGroup(it.first);
317 jmg->setDefaultIKTimeout(it.second);
318 }
319 }
320}
321} // namespace robot_model_loader
void setDefaultIKTimeout(double ik_timeout)
Set the default IK timeout.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
const std::string & getName() const
Get the name of the joint.
JointType getType() const
Get the type of joint.
bool isContinuous() const
Check if this joint wraps around.
RobotModelLoader(const rclcpp::Node::SharedPtr &node, const Options &opt=Options())
Default constructor.
void loadKinematicsSolvers(const kinematics_plugin_loader::KinematicsPluginLoaderPtr &kloader=kinematics_plugin_loader::KinematicsPluginLoaderPtr())
Load the kinematics solvers into the kinematic model. This is done by default, unless disabled explic...
std::function< kinematics::KinematicsBasePtr(const JointModelGroup *)> SolverAllocatorFn
Function type that allocates a kinematics solver for a particular group.
Main namespace for MoveIt.
Definition exceptions.h:43
Structure that encodes the options to be passed to the RobotModelLoader constructor.
bool load_kinematics_solvers
Flag indicating whether the kinematics solvers should be loaded as well, using specified ROS paramete...