moveit2
The MoveIt Motion Planning Framework for ROS 2.
robot_model_test_utils.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, Bryce Willey.
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 MoveIt 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: Bryce Willey */
36 
37 #include <ament_index_cpp/get_package_share_directory.hpp>
38 #include <boost/algorithm/string_regex.hpp>
39 #include <filesystem>
40 #include <geometry_msgs/msg/pose.hpp>
42 #include <rclcpp/logger.hpp>
43 #include <rclcpp/logging.hpp>
44 #include <urdf_parser/urdf_parser.h>
45 #include <moveit/utils/logger.hpp>
46 
47 #include <pluginlib/class_loader.hpp>
48 
50 
51 namespace moveit
52 {
53 namespace core
54 {
55 namespace
56 {
57 rclcpp::Logger getLogger()
58 {
59  return moveit::getLogger("moveit.core.robot_model_test_utils");
60 }
61 } // namespace
62 
63 moveit::core::RobotModelPtr loadTestingRobotModel(const std::string& package_name,
64  const std::string& urdf_relative_path,
65  const std::string& srdf_relative_path)
66 {
67  const auto urdf_path =
68  std::filesystem::path(ament_index_cpp::get_package_share_directory(package_name)) / urdf_relative_path;
69  const auto srdf_path =
70  std::filesystem::path(ament_index_cpp::get_package_share_directory(package_name)) / srdf_relative_path;
71 
72  urdf::ModelInterfaceSharedPtr urdf_model = urdf::parseURDFFile(urdf_path.string());
73  if (urdf_model == nullptr)
74  {
75  return nullptr;
76  }
77 
78  auto srdf_model = std::make_shared<srdf::Model>();
79  if (!srdf_model->initFile(*urdf_model, srdf_path.string()))
80  {
81  return nullptr;
82  }
83 
84  return std::make_shared<moveit::core::RobotModel>(urdf_model, srdf_model);
85 }
86 
87 moveit::core::RobotModelPtr loadTestingRobotModel(const std::string& robot_name)
88 {
89  urdf::ModelInterfaceSharedPtr urdf = loadModelInterface(robot_name);
90  srdf::ModelSharedPtr srdf = loadSRDFModel(robot_name);
91  auto robot_model = std::make_shared<moveit::core::RobotModel>(urdf, srdf);
92  return robot_model;
93 }
94 
95 urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string& robot_name)
96 {
97  const std::string package_name = "moveit_resources_" + robot_name + "_description";
98  std::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name));
99  std::string urdf_path;
100  if (robot_name == "pr2")
101  {
102  urdf_path = (res_path / "urdf/robot.xml").string();
103  }
104  else
105  {
106  urdf_path = (res_path / "urdf" / (robot_name + ".urdf")).string();
107  }
108  urdf::ModelInterfaceSharedPtr urdf_model = urdf::parseURDFFile(urdf_path);
109  if (urdf_model == nullptr)
110  {
111  RCLCPP_ERROR(getLogger(),
112  "Cannot find URDF for %s. Make sure moveit_resources_<your_robot_description> is installed",
113  robot_name.c_str());
114  }
115  return urdf_model;
116 }
117 
118 srdf::ModelSharedPtr loadSRDFModel(const std::string& robot_name)
119 {
120  urdf::ModelInterfaceSharedPtr urdf_model = loadModelInterface(robot_name);
121  auto srdf_model = std::make_shared<srdf::Model>();
122  std::string srdf_path;
123  if (robot_name == "pr2")
124  {
125  const std::string package_name = "moveit_resources_" + robot_name + "_description";
126  std::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name));
127  srdf_path = (res_path / "srdf/robot.xml").string();
128  }
129  else
130  {
131  const std::string package_name = "moveit_resources_" + robot_name + "_moveit_config";
132  std::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name));
133  srdf_path = (res_path / "config" / (robot_name + ".srdf")).string();
134  }
135  srdf_model->initFile(*urdf_model, srdf_path);
136  return srdf_model;
137 }
138 
139 void loadIKPluginForGroup(const rclcpp::Node::SharedPtr& node, JointModelGroup* jmg, const std::string& base_link,
140  const std::string& tip_link, std::string plugin, double timeout)
141 {
142  using LoaderType = pluginlib::ClassLoader<kinematics::KinematicsBase>;
143  static std::weak_ptr<LoaderType> cached_loader;
144  std::shared_ptr<LoaderType> loader = cached_loader.lock();
145  if (!loader)
146  {
147  loader = std::make_shared<LoaderType>("moveit_core", "kinematics::KinematicsBase");
148  cached_loader = loader;
149  }
150 
151  // translate short to long names
152  if (plugin == "KDL")
153  plugin = "kdl_kinematics_plugin/KDLKinematicsPlugin";
154 
155  jmg->setSolverAllocators(
156  [=](const JointModelGroup* jmg) -> kinematics::KinematicsBasePtr {
157  kinematics::KinematicsBasePtr result = loader->createUniqueInstance(plugin);
158  result->initialize(node, jmg->getParentModel(), jmg->getName(), base_link, { tip_link }, 0.0);
159  result->setDefaultTimeout(timeout);
160  return result;
161  },
163 }
164 
165 RobotModelBuilder::RobotModelBuilder(const std::string& name, const std::string& base_link_name)
166  : urdf_model_(std::make_shared<urdf::ModelInterface>()), srdf_writer_(std::make_shared<srdf::SRDFWriter>())
167 {
168  urdf_model_->clear();
169  urdf_model_->name_ = name;
170 
171  auto base_link = std::make_shared<urdf::Link>();
172  base_link->name = base_link_name;
173  urdf_model_->links_.insert(std::make_pair(base_link_name, base_link));
174 
175  srdf_writer_->robot_name_ = name;
176 }
177 
178 void RobotModelBuilder::addChain(const std::string& section, const std::string& type,
179  const std::vector<geometry_msgs::msg::Pose>& joint_origins, urdf::Vector3 joint_axis)
180 {
181  std::vector<std::string> link_names;
182  boost::split_regex(link_names, section, boost::regex("->"));
183  if (link_names.empty())
184  {
185  RCLCPP_ERROR(getLogger(), "No links specified (empty section?)");
186  is_valid_ = false;
187  return;
188  }
189  // First link should already be added.
190  if (!urdf_model_->getLink(link_names[0]))
191  {
192  RCLCPP_ERROR(getLogger(), "Link %s not present in builder yet!", link_names[0].c_str());
193  is_valid_ = false;
194  return;
195  }
196 
197  if (!joint_origins.empty() && link_names.size() - 1 != joint_origins.size())
198  {
199  RCLCPP_ERROR(getLogger(), "There should be one more link (%zu) than there are joint origins (%zu)",
200  link_names.size(), joint_origins.size());
201  is_valid_ = false;
202  return;
203  }
204 
205  // Iterate through each link.
206  for (size_t i = 1; i < link_names.size(); ++i)
207  {
208  // These links shouldn't be present already.
209  if (urdf_model_->getLink(link_names[i]))
210  {
211  RCLCPP_ERROR(getLogger(), "Link %s is already specified", link_names[i].c_str());
212  is_valid_ = false;
213  return;
214  }
215  auto link = std::make_shared<urdf::Link>();
216  link->name = link_names[i];
217  urdf_model_->links_.insert(std::make_pair(link_names[i], link));
218  auto joint = std::make_shared<urdf::Joint>();
219  joint->name = link_names[i - 1] + "-" + link_names[i] + "-joint";
220  // Default to Identity transform for origins.
221  joint->parent_to_joint_origin_transform.clear();
222  if (!joint_origins.empty())
223  {
224  geometry_msgs::msg::Pose o = joint_origins[i - 1];
225  joint->parent_to_joint_origin_transform.position = urdf::Vector3(o.position.x, o.position.y, o.position.z);
226  joint->parent_to_joint_origin_transform.rotation =
227  urdf::Rotation(o.orientation.x, o.orientation.y, o.orientation.z, o.orientation.w);
228  }
229 
230  joint->parent_link_name = link_names[i - 1];
231  joint->child_link_name = link_names[i];
232  if (type == "planar")
233  {
234  joint->type = urdf::Joint::PLANAR;
235  }
236  else if (type == "floating")
237  {
238  joint->type = urdf::Joint::FLOATING;
239  }
240  else if (type == "revolute")
241  {
242  joint->type = urdf::Joint::REVOLUTE;
243  }
244  else if (type == "continuous")
245  {
246  joint->type = urdf::Joint::CONTINUOUS;
247  }
248  else if (type == "prismatic")
249  {
250  joint->type = urdf::Joint::PRISMATIC;
251  }
252  else if (type == "fixed")
253  {
254  joint->type = urdf::Joint::FIXED;
255  }
256  else
257  {
258  RCLCPP_ERROR(getLogger(), "No such joint type as %s", type.c_str());
259  is_valid_ = false;
260  return;
261  }
262 
263  joint->axis = joint_axis;
264  if (joint->type == urdf::Joint::REVOLUTE || joint->type == urdf::Joint::PRISMATIC)
265  {
266  auto limits = std::make_shared<urdf::JointLimits>();
267  limits->lower = -M_PI;
268  limits->upper = M_PI;
269 
270  joint->limits = limits;
271  }
272  urdf_model_->joints_.insert(std::make_pair(joint->name, joint));
273  }
274 }
275 
276 void RobotModelBuilder::addInertial(const std::string& link_name, double mass, geometry_msgs::msg::Pose origin,
277  double ixx, double ixy, double ixz, double iyy, double iyz, double izz)
278 {
279  if (!urdf_model_->getLink(link_name))
280  {
281  RCLCPP_ERROR(getLogger(), "Link %s not present in builder yet!", link_name.c_str());
282  is_valid_ = false;
283  return;
284  }
285 
286  auto inertial = std::make_shared<urdf::Inertial>();
287  inertial->origin.position = urdf::Vector3(origin.position.x, origin.position.y, origin.position.z);
288  inertial->origin.rotation =
289  urdf::Rotation(origin.orientation.x, origin.orientation.y, origin.orientation.z, origin.orientation.w);
290  inertial->mass = mass;
291  inertial->ixx = ixx;
292  inertial->ixy = ixy;
293  inertial->ixz = ixz;
294  inertial->iyy = iyy;
295  inertial->iyz = iyz;
296  inertial->izz = izz;
297 
298  urdf::LinkSharedPtr link;
299  urdf_model_->getLink(link_name, link);
300  link->inertial = inertial;
301 }
302 
303 void RobotModelBuilder::addVisualBox(const std::string& link_name, const std::vector<double>& size,
304  geometry_msgs::msg::Pose origin)
305 {
306  auto vis = std::make_shared<urdf::Visual>();
307  auto geometry = std::make_shared<urdf::Box>();
308  geometry->dim = urdf::Vector3(size[0], size[1], size[2]);
309  vis->geometry = geometry;
310  addLinkVisual(link_name, vis, origin);
311 }
312 
313 void RobotModelBuilder::addCollisionBox(const std::string& link_name, const std::vector<double>& dims,
314  geometry_msgs::msg::Pose origin)
315 {
316  if (dims.size() != 3)
317  {
318  RCLCPP_ERROR(getLogger(), "There can only be 3 dimensions of a box (given %zu!)", dims.size());
319  is_valid_ = false;
320  return;
321  }
322  auto coll = std::make_shared<urdf::Collision>();
323  auto geometry = std::make_shared<urdf::Box>();
324  geometry->dim = urdf::Vector3(dims[0], dims[1], dims[2]);
325  coll->geometry = geometry;
326  addLinkCollision(link_name, coll, origin);
327 }
328 
329 void RobotModelBuilder::addCollisionMesh(const std::string& link_name, const std::string& filename,
330  geometry_msgs::msg::Pose origin)
331 {
332  auto coll = std::make_shared<urdf::Collision>();
333  auto geometry = std::make_shared<urdf::Mesh>();
334  geometry->filename = filename;
335  coll->geometry = geometry;
336  addLinkCollision(link_name, coll, origin);
337 }
338 
339 void RobotModelBuilder::addLinkCollision(const std::string& link_name, const urdf::CollisionSharedPtr& collision,
340  geometry_msgs::msg::Pose origin)
341 {
342  if (!urdf_model_->getLink(link_name))
343  {
344  RCLCPP_ERROR(getLogger(), "Link %s not present in builder yet!", link_name.c_str());
345  is_valid_ = false;
346  return;
347  }
348  collision->origin.position = urdf::Vector3(origin.position.x, origin.position.y, origin.position.z);
349  collision->origin.rotation =
350  urdf::Rotation(origin.orientation.x, origin.orientation.y, origin.orientation.z, origin.orientation.w);
351 
352  urdf::LinkSharedPtr link;
353  urdf_model_->getLink(link_name, link);
354  link->collision_array.push_back(collision);
355 }
356 
357 void RobotModelBuilder::addLinkVisual(const std::string& link_name, const urdf::VisualSharedPtr& vis,
358  geometry_msgs::msg::Pose origin)
359 {
360  if (!urdf_model_->getLink(link_name))
361  {
362  RCLCPP_ERROR(getLogger(), "Link %s not present in builder yet!", link_name.c_str());
363  is_valid_ = false;
364  return;
365  }
366  vis->origin.position = urdf::Vector3(origin.position.x, origin.position.y, origin.position.z);
367  vis->origin.rotation =
368  urdf::Rotation(origin.orientation.x, origin.orientation.y, origin.orientation.z, origin.orientation.w);
369 
370  urdf::LinkSharedPtr link;
371  urdf_model_->getLink(link_name, link);
372  if (!link->visual_array.empty())
373  {
374  link->visual_array.push_back(vis);
375  }
376  else if (link->visual)
377  {
378  link->visual_array.push_back(link->visual);
379  link->visual.reset();
380  link->visual_array.push_back(vis);
381  }
382  else
383  {
384  link->visual = vis;
385  }
386 }
387 
388 void RobotModelBuilder::addVirtualJoint(const std::string& parent_frame, const std::string& child_link,
389  const std::string& type, const std::string& name)
390 {
391  srdf::Model::VirtualJoint new_virtual_joint;
392  if (name.empty())
393  {
394  new_virtual_joint.name_ = parent_frame + "-" + child_link + "-virtual_joint";
395  }
396  else
397  {
398  new_virtual_joint.name_ = name;
399  }
400  new_virtual_joint.type_ = type;
401  new_virtual_joint.parent_frame_ = parent_frame;
402  new_virtual_joint.child_link_ = child_link;
403  srdf_writer_->virtual_joints_.push_back(new_virtual_joint);
404 }
405 
406 void RobotModelBuilder::addGroupChain(const std::string& base_link, const std::string& tip_link, const std::string& name)
407 {
408  srdf::Model::Group new_group;
409  if (name.empty())
410  {
411  new_group.name_ = base_link + "-" + tip_link + "-chain-group";
412  }
413  else
414  {
415  new_group.name_ = name;
416  }
417  new_group.chains_.push_back(std::make_pair(base_link, tip_link));
418  srdf_writer_->groups_.push_back(new_group);
419 }
420 
421 void RobotModelBuilder::addGroup(const std::vector<std::string>& links, const std::vector<std::string>& joints,
422  const std::string& name)
423 {
424  srdf::Model::Group new_group;
425  new_group.name_ = name;
426  new_group.links_ = links;
427  new_group.joints_ = joints;
428  srdf_writer_->groups_.push_back(new_group);
429 }
430 
431 void RobotModelBuilder::addEndEffector(const std::string& name, const std::string& parent_link,
432  const std::string& parent_group, const std::string& component_group)
433 {
434  srdf::Model::EndEffector eef;
435  eef.name_ = name;
436  eef.parent_link_ = parent_link;
437  eef.parent_group_ = parent_group;
438  eef.component_group_ = component_group;
439  srdf_writer_->end_effectors_.push_back(eef);
440 }
441 
442 void RobotModelBuilder::addJointProperty(const std::string& joint_name, const std::string& property_name,
443  const std::string& value)
444 {
445  srdf_writer_->joint_properties_[joint_name].push_back({ joint_name, property_name, value });
446 }
447 
449 {
450  return is_valid_;
451 }
452 
453 moveit::core::RobotModelPtr RobotModelBuilder::build()
454 {
455  moveit::core::RobotModelPtr robot_model;
456  std::map<std::string, std::string> parent_link_tree;
457  parent_link_tree.clear();
458 
459  try
460  {
461  urdf_model_->initTree(parent_link_tree);
462  }
463  catch (urdf::ParseError& e)
464  {
465  RCLCPP_ERROR(getLogger(), "Failed to build tree: %s", e.what());
466  return robot_model;
467  }
468 
469  // find the root link
470  try
471  {
472  urdf_model_->initRoot(parent_link_tree);
473  }
474  catch (urdf::ParseError& e)
475  {
476  RCLCPP_ERROR(getLogger(), "Failed to find root link: %s", e.what());
477  return robot_model;
478  }
479  srdf_writer_->updateSRDFModel(*urdf_model_);
480  robot_model = std::make_shared<moveit::core::RobotModel>(urdf_model_, srdf_writer_->srdf_model_);
481  return robot_model;
482 }
483 } // namespace core
484 } // namespace moveit
const std::string & getName() const
Get the name of the joint group.
void setSolverAllocators(const SolverAllocatorFn &solver, const SolverAllocatorMapFn &solver_map=SolverAllocatorMapFn())
const RobotModel & getParentModel() const
Get the kinematic model this group is part of.
void addChain(const std::string &section, const std::string &type, const std::vector< geometry_msgs::msg::Pose > &joint_origins={}, urdf::Vector3 joint_axis=urdf::Vector3(1.0, 0.0, 0.0))
Adds a chain of links and joints to the builder. The joint names are generated automatically as "<par...
void addInertial(const std::string &link_name, double mass, geometry_msgs::msg::Pose origin, double ixx, double ixy, double ixz, double iyy, double iyz, double izz)
void addEndEffector(const std::string &name, const std::string &parent_link, const std::string &parent_group="", const std::string &component_group="")
void addCollisionBox(const std::string &link_name, const std::vector< double > &dims, geometry_msgs::msg::Pose origin)
Adds a collision box to a specific link.
void addJointProperty(const std::string &joint_name, const std::string &property_name, const std::string &value)
Adds a new joint property.
bool isValid()
Returns true if the building process so far has been valid.
void addGroup(const std::vector< std::string > &links, const std::vector< std::string > &joints, const std::string &name)
Adds a new group using a list of links and a list of joints.
moveit::core::RobotModelPtr build()
Builds and returns the robot model added to the builder.
void addVirtualJoint(const std::string &parent_frame, const std::string &child_link, const std::string &type, const std::string &name="")
Adds a virtual joint to the SRDF.
void addGroupChain(const std::string &base_link, const std::string &tip_link, const std::string &name="")
Adds a new group using a chain of links. The group is the parent joint of each link in the chain.
void addCollisionMesh(const std::string &link_name, const std::string &filename, geometry_msgs::msg::Pose origin)
Adds a collision mesh to a specific link.
RobotModelBuilder(const std::string &name, const std::string &base_link_name)
Constructor, takes the names of the robot and the base link.
void addVisualBox(const std::string &link_name, const std::vector< double > &size, geometry_msgs::msg::Pose origin)
Adds a visual box to a specific link.
std::map< const JointModelGroup *, SolverAllocatorFn > SolverAllocatorMapFn
Map from group instances to allocator functions & bijections.
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &package_name, const std::string &urdf_relative_path, const std::string &srdf_relative_path)
Loads a robot model given a URDF and SRDF file in a package.
srdf::ModelSharedPtr loadSRDFModel(const std::string &robot_name)
Loads an SRDF Model from moveit_resources.
void loadIKPluginForGroup(const rclcpp::Node::SharedPtr &node, JointModelGroup *jmg, const std::string &base_link, const std::string &tip_link, std::string plugin="KDL", double timeout=0.1)
Load an IK solver plugin for the given joint model group.
urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string &robot_name)
Loads a URDF Model Interface from moveit_resources.
Main namespace for MoveIt.
Definition: exceptions.hpp:43
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
string package_name
Definition: setup.py:4
name
Definition: setup.py:7