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