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 <boost/algorithm/string_regex.hpp>
38 #include <geometry_msgs/msg/pose.hpp>
39 #include <urdf_parser/urdf_parser.h>
41 #include <ament_index_cpp/get_package_share_directory.hpp>
42 #include <filesystem>
43 #include <rclcpp/logger.hpp>
44 #include <rclcpp/logging.hpp>
45 
46 namespace moveit
47 {
48 namespace core
49 {
50 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_utils.robot_model_test_utils");
51 
52 moveit::core::RobotModelPtr loadTestingRobotModel(const std::string& robot_name)
53 {
54  urdf::ModelInterfaceSharedPtr urdf = loadModelInterface(robot_name);
55  srdf::ModelSharedPtr srdf = loadSRDFModel(robot_name);
56  auto robot_model = std::make_shared<moveit::core::RobotModel>(urdf, srdf);
57  return robot_model;
58 }
59 
60 urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string& robot_name)
61 {
62  const std::string package_name = "moveit_resources_" + robot_name + "_description";
63  std::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name));
64  std::string urdf_path;
65  if (robot_name == "pr2")
66  {
67  urdf_path = (res_path / "urdf/robot.xml").string();
68  }
69  else
70  {
71  urdf_path = (res_path / "urdf" / (robot_name + ".urdf")).string();
72  }
73  urdf::ModelInterfaceSharedPtr urdf_model = urdf::parseURDFFile(urdf_path);
74  if (urdf_model == nullptr)
75  {
76  RCLCPP_ERROR(LOGGER, "Cannot find URDF for %s. Make sure moveit_resources_<your_robot_description> is installed",
77  robot_name.c_str());
78  }
79  return urdf_model;
80 }
81 
82 srdf::ModelSharedPtr loadSRDFModel(const std::string& robot_name)
83 {
84  urdf::ModelInterfaceSharedPtr urdf_model = loadModelInterface(robot_name);
85  auto srdf_model = std::make_shared<srdf::Model>();
86  std::string srdf_path;
87  if (robot_name == "pr2")
88  {
89  const std::string package_name = "moveit_resources_" + robot_name + "_description";
90  std::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name));
91  srdf_path = (res_path / "srdf/robot.xml").string();
92  }
93  else
94  {
95  const std::string package_name = "moveit_resources_" + robot_name + "_moveit_config";
96  std::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name));
97  srdf_path = (res_path / "config" / (robot_name + ".srdf")).string();
98  }
99  srdf_model->initFile(*urdf_model, srdf_path);
100  return srdf_model;
101 }
102 
103 RobotModelBuilder::RobotModelBuilder(const std::string& name, const std::string& base_link_name)
104  : urdf_model_(std::make_shared<urdf::ModelInterface>()), srdf_writer_(std::make_shared<srdf::SRDFWriter>())
105 {
106  urdf_model_->clear();
107  urdf_model_->name_ = name;
108 
109  auto base_link = std::make_shared<urdf::Link>();
110  base_link->name = base_link_name;
111  urdf_model_->links_.insert(std::make_pair(base_link_name, base_link));
112 
113  srdf_writer_->robot_name_ = name;
114 }
115 
116 void RobotModelBuilder::addChain(const std::string& section, const std::string& type,
117  const std::vector<geometry_msgs::msg::Pose>& joint_origins, urdf::Vector3 joint_axis)
118 {
119  std::vector<std::string> link_names;
120  boost::split_regex(link_names, section, boost::regex("->"));
121  if (link_names.empty())
122  {
123  RCLCPP_ERROR(LOGGER, "No links specified (empty section?)");
124  is_valid_ = false;
125  return;
126  }
127  // First link should already be added.
128  if (!urdf_model_->getLink(link_names[0]))
129  {
130  RCLCPP_ERROR(LOGGER, "Link %s not present in builder yet!", link_names[0].c_str());
131  is_valid_ = false;
132  return;
133  }
134 
135  if (!joint_origins.empty() && link_names.size() - 1 != joint_origins.size())
136  {
137  RCLCPP_ERROR(LOGGER, "There should be one more link (%zu) than there are joint origins (%zu)", link_names.size(),
138  joint_origins.size());
139  is_valid_ = false;
140  return;
141  }
142 
143  // Iterate through each link.
144  for (size_t i = 1; i < link_names.size(); ++i)
145  {
146  // These links shouldn't be present already.
147  if (urdf_model_->getLink(link_names[i]))
148  {
149  RCLCPP_ERROR(LOGGER, "Link %s is already specified", link_names[i].c_str());
150  is_valid_ = false;
151  return;
152  }
153  auto link = std::make_shared<urdf::Link>();
154  link->name = link_names[i];
155  urdf_model_->links_.insert(std::make_pair(link_names[i], link));
156  auto joint = std::make_shared<urdf::Joint>();
157  joint->name = link_names[i - 1] + "-" + link_names[i] + "-joint";
158  // Default to Identity transform for origins.
159  joint->parent_to_joint_origin_transform.clear();
160  if (!joint_origins.empty())
161  {
162  geometry_msgs::msg::Pose o = joint_origins[i - 1];
163  joint->parent_to_joint_origin_transform.position = urdf::Vector3(o.position.x, o.position.y, o.position.z);
164  joint->parent_to_joint_origin_transform.rotation =
165  urdf::Rotation(o.orientation.x, o.orientation.y, o.orientation.z, o.orientation.w);
166  }
167 
168  joint->parent_link_name = link_names[i - 1];
169  joint->child_link_name = link_names[i];
170  if (type == "planar")
171  joint->type = urdf::Joint::PLANAR;
172  else if (type == "floating")
173  joint->type = urdf::Joint::FLOATING;
174  else if (type == "revolute")
175  joint->type = urdf::Joint::REVOLUTE;
176  else if (type == "continuous")
177  joint->type = urdf::Joint::CONTINUOUS;
178  else if (type == "prismatic")
179  joint->type = urdf::Joint::PRISMATIC;
180  else if (type == "fixed")
181  joint->type = urdf::Joint::FIXED;
182  else
183  {
184  RCLCPP_ERROR(LOGGER, "No such joint type as %s", type.c_str());
185  is_valid_ = false;
186  return;
187  }
188 
189  joint->axis = joint_axis;
190  if (joint->type == urdf::Joint::REVOLUTE || joint->type == urdf::Joint::PRISMATIC)
191  {
192  auto limits = std::make_shared<urdf::JointLimits>();
193  limits->lower = -M_PI;
194  limits->upper = M_PI;
195 
196  joint->limits = limits;
197  }
198  urdf_model_->joints_.insert(std::make_pair(joint->name, joint));
199  }
200 }
201 
202 void RobotModelBuilder::addInertial(const std::string& link_name, double mass, geometry_msgs::msg::Pose origin,
203  double ixx, double ixy, double ixz, double iyy, double iyz, double izz)
204 {
205  if (!urdf_model_->getLink(link_name))
206  {
207  RCLCPP_ERROR(LOGGER, "Link %s not present in builder yet!", link_name.c_str());
208  is_valid_ = false;
209  return;
210  }
211 
212  auto inertial = std::make_shared<urdf::Inertial>();
213  inertial->origin.position = urdf::Vector3(origin.position.x, origin.position.y, origin.position.z);
214  inertial->origin.rotation =
215  urdf::Rotation(origin.orientation.x, origin.orientation.y, origin.orientation.z, origin.orientation.w);
216  inertial->mass = mass;
217  inertial->ixx = ixx;
218  inertial->ixy = ixy;
219  inertial->ixz = ixz;
220  inertial->iyy = iyy;
221  inertial->iyz = iyz;
222  inertial->izz = izz;
223 
224  urdf::LinkSharedPtr link;
225  urdf_model_->getLink(link_name, link);
226  link->inertial = inertial;
227 }
228 
229 void RobotModelBuilder::addVisualBox(const std::string& link_name, const std::vector<double>& size,
230  geometry_msgs::msg::Pose origin)
231 {
232  auto vis = std::make_shared<urdf::Visual>();
233  auto geometry = std::make_shared<urdf::Box>();
234  geometry->dim = urdf::Vector3(size[0], size[1], size[2]);
235  vis->geometry = geometry;
236  addLinkVisual(link_name, vis, origin);
237 }
238 
239 void RobotModelBuilder::addCollisionBox(const std::string& link_name, const std::vector<double>& dims,
240  geometry_msgs::msg::Pose origin)
241 {
242  if (dims.size() != 3)
243  {
244  RCLCPP_ERROR(LOGGER, "There can only be 3 dimensions of a box (given %zu!)", dims.size());
245  is_valid_ = false;
246  return;
247  }
248  auto coll = std::make_shared<urdf::Collision>();
249  auto geometry = std::make_shared<urdf::Box>();
250  geometry->dim = urdf::Vector3(dims[0], dims[1], dims[2]);
251  coll->geometry = geometry;
252  addLinkCollision(link_name, coll, origin);
253 }
254 
255 void RobotModelBuilder::addCollisionMesh(const std::string& link_name, const std::string& filename,
256  geometry_msgs::msg::Pose origin)
257 {
258  auto coll = std::make_shared<urdf::Collision>();
259  auto geometry = std::make_shared<urdf::Mesh>();
260  geometry->filename = filename;
261  coll->geometry = geometry;
262  addLinkCollision(link_name, coll, origin);
263 }
264 
265 void RobotModelBuilder::addLinkCollision(const std::string& link_name, const urdf::CollisionSharedPtr& collision,
266  geometry_msgs::msg::Pose origin)
267 {
268  if (!urdf_model_->getLink(link_name))
269  {
270  RCLCPP_ERROR(LOGGER, "Link %s not present in builder yet!", link_name.c_str());
271  is_valid_ = false;
272  return;
273  }
274  collision->origin.position = urdf::Vector3(origin.position.x, origin.position.y, origin.position.z);
275  collision->origin.rotation =
276  urdf::Rotation(origin.orientation.x, origin.orientation.y, origin.orientation.z, origin.orientation.w);
277 
278  urdf::LinkSharedPtr link;
279  urdf_model_->getLink(link_name, link);
280  link->collision_array.push_back(collision);
281 }
282 
283 void RobotModelBuilder::addLinkVisual(const std::string& link_name, const urdf::VisualSharedPtr& vis,
284  geometry_msgs::msg::Pose origin)
285 {
286  if (!urdf_model_->getLink(link_name))
287  {
288  RCLCPP_ERROR(LOGGER, "Link %s not present in builder yet!", link_name.c_str());
289  is_valid_ = false;
290  return;
291  }
292  vis->origin.position = urdf::Vector3(origin.position.x, origin.position.y, origin.position.z);
293  vis->origin.rotation =
294  urdf::Rotation(origin.orientation.x, origin.orientation.y, origin.orientation.z, origin.orientation.w);
295 
296  urdf::LinkSharedPtr link;
297  urdf_model_->getLink(link_name, link);
298  if (!link->visual_array.empty())
299  {
300  link->visual_array.push_back(vis);
301  }
302  else if (link->visual)
303  {
304  link->visual_array.push_back(link->visual);
305  link->visual.reset();
306  link->visual_array.push_back(vis);
307  }
308  else
309  {
310  link->visual = vis;
311  }
312 }
313 
314 void RobotModelBuilder::addVirtualJoint(const std::string& parent_frame, const std::string& child_link,
315  const std::string& type, const std::string& name)
316 {
317  srdf::Model::VirtualJoint new_virtual_joint;
318  if (name.empty())
319  new_virtual_joint.name_ = parent_frame + "-" + child_link + "-virtual_joint";
320  else
321  new_virtual_joint.name_ = name;
322  new_virtual_joint.type_ = type;
323  new_virtual_joint.parent_frame_ = parent_frame;
324  new_virtual_joint.child_link_ = child_link;
325  srdf_writer_->virtual_joints_.push_back(new_virtual_joint);
326 }
327 
328 void RobotModelBuilder::addGroupChain(const std::string& base_link, const std::string& tip_link, const std::string& name)
329 {
330  srdf::Model::Group new_group;
331  if (name.empty())
332  new_group.name_ = base_link + "-" + tip_link + "-chain-group";
333  else
334  new_group.name_ = name;
335  new_group.chains_.push_back(std::make_pair(base_link, tip_link));
336  srdf_writer_->groups_.push_back(new_group);
337 }
338 
339 void RobotModelBuilder::addGroup(const std::vector<std::string>& links, const std::vector<std::string>& joints,
340  const std::string& name)
341 {
342  srdf::Model::Group new_group;
343  new_group.name_ = name;
344  new_group.links_ = links;
345  new_group.joints_ = joints;
346  srdf_writer_->groups_.push_back(new_group);
347 }
348 
349 void RobotModelBuilder::addEndEffector(const std::string& name, const std::string& parent_link,
350  const std::string& parent_group, const std::string& component_group)
351 {
352  srdf::Model::EndEffector eef;
353  eef.name_ = name;
354  eef.parent_link_ = parent_link;
355  eef.parent_group_ = parent_group;
356  eef.component_group_ = component_group;
357  srdf_writer_->end_effectors_.push_back(eef);
358 }
359 
360 void RobotModelBuilder::addJointProperty(const std::string& joint_name, const std::string& property_name,
361  const std::string& value)
362 {
363  srdf_writer_->joint_properties_[joint_name].push_back({ joint_name, property_name, value });
364 }
365 
367 {
368  return is_valid_;
369 }
370 
371 moveit::core::RobotModelPtr RobotModelBuilder::build()
372 {
373  moveit::core::RobotModelPtr robot_model;
374  std::map<std::string, std::string> parent_link_tree;
375  parent_link_tree.clear();
376 
377  try
378  {
379  urdf_model_->initTree(parent_link_tree);
380  }
381  catch (urdf::ParseError& e)
382  {
383  RCLCPP_ERROR(LOGGER, "Failed to build tree: %s", e.what());
384  return robot_model;
385  }
386 
387  // find the root link
388  try
389  {
390  urdf_model_->initRoot(parent_link_tree);
391  }
392  catch (urdf::ParseError& e)
393  {
394  RCLCPP_ERROR(LOGGER, "Failed to find root link: %s", e.what());
395  return robot_model;
396  }
397  srdf_writer_->updateSRDFModel(*urdf_model_);
398  robot_model = std::make_shared<moveit::core::RobotModel>(urdf_model_, srdf_writer_->srdf_model_);
399  return robot_model;
400 }
401 } // namespace core
402 } // namespace moveit
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.
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
srdf::ModelSharedPtr loadSRDFModel(const std::string &robot_name)
Loads an SRDF Model from moveit_resources.
urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string &robot_name)
Loads a URDF Model Interface from moveit_resources.
Main namespace for MoveIt.
Definition: exceptions.h:43
string package_name
Definition: setup.py:4
name
Definition: setup.py:7