moveit2
The MoveIt Motion Planning Framework for ROS 2.
robot_model.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Ioan A. Sucan
5  * Copyright (c) 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Ioan Sucan */
37 
39 #include <geometric_shapes/shape_operations.h>
40 #include <rclcpp/logger.hpp>
41 #include <algorithm>
42 #include <limits>
43 #include <cmath>
44 #include <memory>
45 
47 
48 namespace moveit
49 {
50 namespace core
51 {
52 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_robot_model.robot_model");
53 
54 RobotModel::RobotModel(const urdf::ModelInterfaceSharedPtr& urdf_model, const srdf::ModelConstSharedPtr& srdf_model)
55 {
56  root_joint_ = nullptr;
57  urdf_ = urdf_model;
58  srdf_ = srdf_model;
59  buildModel(*urdf_model, *srdf_model);
60 }
61 
63 {
64  for (std::pair<const std::string, JointModelGroup*>& it : joint_model_group_map_)
65  delete it.second;
66  for (JointModel* joint_model : joint_model_vector_)
67  delete joint_model;
68  for (LinkModel* link_model : link_model_vector_)
69  delete link_model;
70 }
71 
73 {
74  return root_joint_;
75 }
76 
78 {
79  return root_link_;
80 }
81 
82 void RobotModel::buildModel(const urdf::ModelInterface& urdf_model, const srdf::Model& srdf_model)
83 {
84  root_joint_ = nullptr;
85  root_link_ = nullptr;
87  variable_count_ = 0;
88  model_name_ = urdf_model.getName();
89  RCLCPP_INFO(LOGGER, "Loading robot model '%s'...", model_name_.c_str());
90 
91  if (urdf_model.getRoot())
92  {
93  const urdf::Link* root_link_ptr = urdf_model.getRoot().get();
94  model_frame_ = root_link_ptr->name;
95 
96  RCLCPP_DEBUG(LOGGER, "... building kinematic chain");
97  root_joint_ = buildRecursive(nullptr, root_link_ptr, srdf_model);
98  if (root_joint_)
100  RCLCPP_DEBUG(LOGGER, "... building mimic joints");
101  buildMimic(urdf_model);
102 
103  RCLCPP_DEBUG(LOGGER, "... computing joint indexing");
104  buildJointInfo();
105 
107  {
108  RCLCPP_WARN(LOGGER, "No geometry is associated to any robot links");
109  }
110 
111  // build groups
112 
113  RCLCPP_DEBUG(LOGGER, "... constructing joint groups");
114  buildGroups(srdf_model);
115 
116  RCLCPP_DEBUG(LOGGER, "... constructing joint group states");
117  buildGroupStates(srdf_model);
118 
119  // For debugging entire model
120  // printModelInfo(std::cout);
121  }
122  else
123  {
124  RCLCPP_WARN(LOGGER, "No root link found");
125  }
126 }
127 
128 namespace
129 {
130 typedef std::map<const JointModel*, std::pair<std::set<const LinkModel*, OrderLinksByIndex>,
131  std::set<const JointModel*, OrderJointsByIndex>>>
132  DescMap;
133 
134 void computeDescendantsHelper(const JointModel* joint, std::vector<const JointModel*>& parents,
135  std::set<const JointModel*>& seen, DescMap& descendants)
136 {
137  if (!joint)
138  return;
139  if (seen.find(joint) != seen.end())
140  return;
141  seen.insert(joint);
142 
143  for (const JointModel* parent : parents)
144  descendants[parent].second.insert(joint);
145 
146  const LinkModel* lm = joint->getChildLinkModel();
147  if (!lm)
148  return;
149 
150  for (const JointModel* parent : parents)
151  descendants[parent].first.insert(lm);
152  descendants[joint].first.insert(lm);
153 
154  parents.push_back(joint);
155  const std::vector<const JointModel*>& ch = lm->getChildJointModels();
156  for (const JointModel* child_joint_model : ch)
157  computeDescendantsHelper(child_joint_model, parents, seen, descendants);
158  const std::vector<const JointModel*>& mim = joint->getMimicRequests();
159  for (const JointModel* mimic_joint_model : mim)
160  computeDescendantsHelper(mimic_joint_model, parents, seen, descendants);
161  parents.pop_back();
162 }
163 
164 void computeCommonRootsHelper(const JointModel* joint, std::vector<int>& common_roots, int size)
165 {
166  if (!joint)
167  return;
168  const LinkModel* lm = joint->getChildLinkModel();
169  if (!lm)
170  return;
171 
172  const std::vector<const JointModel*>& ch = lm->getChildJointModels();
173  for (std::size_t i = 0; i < ch.size(); ++i)
174  {
175  const std::vector<const JointModel*>& a = ch[i]->getDescendantJointModels();
176  for (std::size_t j = i + 1; j < ch.size(); ++j)
177  {
178  const std::vector<const JointModel*>& b = ch[j]->getDescendantJointModels();
179  for (const JointModel* m : b)
180  {
181  common_roots[ch[i]->getJointIndex() * size + m->getJointIndex()] =
182  common_roots[ch[i]->getJointIndex() + m->getJointIndex() * size] = joint->getJointIndex();
183  }
184  for (const JointModel* k : a)
185  {
186  common_roots[k->getJointIndex() * size + ch[j]->getJointIndex()] =
187  common_roots[k->getJointIndex() + ch[j]->getJointIndex() * size] = joint->getJointIndex();
188  for (const JointModel* m : b)
189  {
190  common_roots[k->getJointIndex() * size + m->getJointIndex()] =
191  common_roots[k->getJointIndex() + m->getJointIndex() * size] = joint->getJointIndex();
192  }
193  }
194  }
195  computeCommonRootsHelper(ch[i], common_roots, size);
196  }
197 }
198 } // namespace
199 
200 void RobotModel::computeCommonRoots()
201 {
202  // compute common roots for all pairs of joints;
203  // there are 3 cases of pairs (X, Y):
204  // X != Y && X and Y are not descendants of one another
205  // X == Y
206  // X != Y && X and Y are descendants of one another
207 
208  // by default, the common root is always the global root;
210 
211  // look at all descendants recursively; for two sibling nodes A, B, both children of X, all the pairs of respective
212  // descendants of A and B
213  // have X as the common root.
214  computeCommonRootsHelper(root_joint_, common_joint_roots_, joint_model_vector_.size());
215 
216  for (const JointModel* joint_model : joint_model_vector_)
217  {
218  // the common root of a joint and itself is the same joint:
219  common_joint_roots_[joint_model->getJointIndex() * (1 + joint_model_vector_.size())] = joint_model->getJointIndex();
220 
221  // a node N and one of its descendants have as common root the node N itself:
222  const std::vector<const JointModel*>& d = joint_model->getDescendantJointModels();
223  for (const JointModel* descendant_joint_model : d)
224  {
225  common_joint_roots_[descendant_joint_model->getJointIndex() * joint_model_vector_.size() +
226  joint_model->getJointIndex()] =
227  common_joint_roots_[descendant_joint_model->getJointIndex() +
228  joint_model->getJointIndex() * joint_model_vector_.size()] = joint_model->getJointIndex();
229  }
230  }
231 }
232 
233 void RobotModel::computeDescendants()
234 {
235  // compute the list of descendants for all joints
236  std::vector<const JointModel*> parents;
237  std::set<const JointModel*> seen;
238 
239  DescMap descendants;
240  computeDescendantsHelper(root_joint_, parents, seen, descendants);
241  for (std::pair<const JointModel* const, std::pair<std::set<const LinkModel*, OrderLinksByIndex>,
242  std::set<const JointModel*, OrderJointsByIndex>>>& descendant :
243  descendants)
244  {
245  JointModel* jm = const_cast<JointModel*>(descendant.first);
246  for (const JointModel* jt : descendant.second.second)
247  jm->addDescendantJointModel(jt);
248  for (const LinkModel* jt : descendant.second.first)
249  jm->addDescendantLinkModel(jt);
250  }
251 }
252 
253 void RobotModel::buildJointInfo()
254 {
255  // construct additional maps for easy access by name
256  variable_count_ = 0;
258  variable_names_.reserve(joint_model_vector_.size());
260 
261  for (const auto& joint : joint_model_vector_)
262  {
263  const std::vector<std::string>& name_order = joint->getVariableNames();
264 
265  // compute index map
266  if (!name_order.empty())
267  {
268  for (std::size_t j = 0; j < name_order.size(); ++j)
269  {
270  joint_variables_index_map_[name_order[j]] = variable_count_ + j;
271  variable_names_.push_back(name_order[j]);
272  joints_of_variable_.push_back(joint);
273  }
274  if (joint->getMimic() == nullptr)
275  {
277  active_joint_model_vector_.push_back(joint);
278  active_joint_model_names_vector_.push_back(joint->getName());
279  active_joint_model_vector_const_.push_back(joint);
280  active_joint_models_bounds_.push_back(&joint->getVariableBounds());
281  }
282 
283  if (joint->getType() == JointModel::REVOLUTE && static_cast<const RevoluteJointModel*>(joint)->isContinuous())
284  continuous_joint_model_vector_.push_back(joint);
285 
286  joint_variables_index_map_[joint->getName()] = variable_count_;
287 
288  // compute variable count
289  std::size_t vc = joint->getVariableCount();
290  variable_count_ += vc;
291  if (vc == 1)
292  {
293  single_dof_joints_.push_back(joint);
294  }
295  else
296  {
297  multi_dof_joints_.push_back(joint);
298  }
299  }
300  }
301 
302  std::vector<bool> link_considered(link_model_vector_.size(), false);
303  for (const LinkModel* link : link_model_vector_)
304  {
305  if (link_considered[link->getLinkIndex()])
306  continue;
307 
308  LinkTransformMap associated_transforms;
309  computeFixedTransforms(link, link->getJointOriginTransform().inverse(), associated_transforms);
310  for (auto& tf_base : associated_transforms)
311  {
312  link_considered[tf_base.first->getLinkIndex()] = true;
313  for (auto& tf_target : associated_transforms)
314  {
315  if (&tf_base != &tf_target)
316  {
317  const_cast<LinkModel*>(tf_base.first) // regain write access to base LinkModel*
318  ->addAssociatedFixedTransform(tf_target.first, tf_base.second.inverse() * tf_target.second);
319  }
320  }
321  }
322  }
323 
324  computeDescendants();
325  computeCommonRoots(); // must be called _after_ list of descendants was computed
326 }
327 
328 void RobotModel::buildGroupStates(const srdf::Model& srdf_model)
329 {
330  // copy the default states to the groups
331  const std::vector<srdf::Model::GroupState>& ds = srdf_model.getGroupStates();
332  for (const srdf::Model::GroupState& group_state : ds)
333  {
334  if (hasJointModelGroup(group_state.group_))
335  {
336  JointModelGroup* jmg = getJointModelGroup(group_state.group_);
337  std::vector<const JointModel*> remaining_joints = jmg->getActiveJointModels();
338  std::map<std::string, double> state;
339  for (std::map<std::string, std::vector<double>>::const_iterator jt = group_state.joint_values_.begin();
340  jt != group_state.joint_values_.end(); ++jt)
341  {
342  if (jmg->hasJointModel(jt->first))
343  {
344  const JointModel* jm = jmg->getJointModel(jt->first);
345  const std::vector<std::string>& vn = jm->getVariableNames();
346  // Remove current joint name from remaining list.
347  auto it_found = std::find(remaining_joints.begin(), remaining_joints.end(), jm);
348  if (it_found != remaining_joints.end())
349  remaining_joints.erase(it_found);
350  if (vn.size() == jt->second.size())
351  {
352  for (std::size_t j = 0; j < vn.size(); ++j)
353  state[vn[j]] = jt->second[j];
354  }
355  else
356  {
357  RCLCPP_ERROR(LOGGER,
358  "The model for joint '%s' requires %d variable values, "
359  "but only %d variable values were supplied in default state '%s' for group '%s'",
360  jt->first.c_str(), static_cast<int>(vn.size()), static_cast<int>(jt->second.size()),
361  group_state.name_.c_str(), jmg->getName().c_str());
362  }
363  }
364  else
365  {
366  RCLCPP_ERROR(LOGGER,
367  "Group state '%s' specifies value for joint '%s', "
368  "but that joint is not part of group '%s'",
369  group_state.name_.c_str(), jt->first.c_str(), jmg->getName().c_str());
370  }
371  }
372  if (!remaining_joints.empty())
373  {
374  std::stringstream missing;
375  missing << (*remaining_joints.begin())->getName();
376  for (auto j = ++remaining_joints.begin(); j != remaining_joints.end(); ++j)
377  {
378  missing << ", " << (*j)->getName();
379  }
380  RCLCPP_WARN_STREAM(LOGGER, "Group state '" << group_state.name_
381  << "' doesn't specify all group joints in group '"
382  << group_state.group_ << "'. " << missing.str() << ' '
383  << (remaining_joints.size() > 1 ? "are" : "is") << " missing.");
384  }
385  if (!state.empty())
386  jmg->addDefaultState(group_state.name_, state);
387  }
388  else
389  {
390  RCLCPP_ERROR(LOGGER, "Group state '%s' specified for group '%s', but that group does not exist",
391  group_state.name_.c_str(), group_state.group_.c_str());
392  }
393  }
394 }
395 
396 void RobotModel::buildMimic(const urdf::ModelInterface& urdf_model)
397 {
398  // compute mimic joints
399  for (JointModel* joint_model : joint_model_vector_)
400  {
401  const urdf::Joint* jm = urdf_model.getJoint(joint_model->getName()).get();
402  if (jm)
403  {
404  if (jm->mimic)
405  {
406  JointModelMap::const_iterator jit = joint_model_map_.find(jm->mimic->joint_name);
407  if (jit != joint_model_map_.end())
408  {
409  if (joint_model->getVariableCount() == jit->second->getVariableCount())
410  {
411  joint_model->setMimic(jit->second, jm->mimic->multiplier, jm->mimic->offset);
412  }
413  else
414  {
415  RCLCPP_ERROR(LOGGER, "Joint '%s' cannot mimic joint '%s' because they have different number of DOF",
416  joint_model->getName().c_str(), jm->mimic->joint_name.c_str());
417  }
418  }
419  else
420  {
421  RCLCPP_ERROR(LOGGER, "Joint '%s' cannot mimic unknown joint '%s'", joint_model->getName().c_str(),
422  jm->mimic->joint_name.c_str());
423  }
424  }
425  }
426  }
427 
428  // in case we have a joint that mimics a joint that already mimics another joint, we can simplify things:
429  bool change = true;
430  while (change)
431  {
432  change = false;
433  for (JointModel* joint_model : joint_model_vector_)
434  {
435  if (joint_model->getMimic())
436  {
437  if (joint_model->getMimic()->getMimic())
438  {
439  joint_model->setMimic(joint_model->getMimic()->getMimic(),
440  joint_model->getMimicFactor() * joint_model->getMimic()->getMimicFactor(),
441  joint_model->getMimicOffset() +
442  joint_model->getMimicFactor() * joint_model->getMimic()->getMimicOffset());
443  change = true;
444  }
445  if (joint_model == joint_model->getMimic())
446  {
447  RCLCPP_ERROR(LOGGER, "Cycle found in joint that mimic each other. Ignoring all mimic joints.");
448  for (JointModel* joint_model_recal : joint_model_vector_)
449  joint_model_recal->setMimic(nullptr, 0.0, 0.0);
450  change = false;
451  break;
452  }
453  }
454  }
455  }
456  // build mimic requests
457  for (JointModel* joint_model : joint_model_vector_)
458  {
459  if (joint_model->getMimic())
460  {
461  const_cast<JointModel*>(joint_model->getMimic())->addMimicRequest(joint_model);
462  mimic_joints_.push_back(joint_model);
463  }
464  }
465 }
466 
467 bool RobotModel::hasEndEffector(const std::string& eef) const
468 {
469  return end_effectors_map_.find(eef) != end_effectors_map_.end();
470 }
471 
472 const JointModelGroup* RobotModel::getEndEffector(const std::string& name) const
473 {
474  JointModelGroupMap::const_iterator it = end_effectors_map_.find(name);
475  if (it == end_effectors_map_.end())
476  {
477  it = joint_model_group_map_.find(name);
478  if (it != joint_model_group_map_.end() && it->second->isEndEffector())
479  return it->second;
480  RCLCPP_ERROR(LOGGER, "End-effector '%s' not found in model '%s'", name.c_str(), model_name_.c_str());
481  return nullptr;
482  }
483  return it->second;
484 }
485 
487 {
488  JointModelGroupMap::const_iterator it = end_effectors_map_.find(name);
489  if (it == end_effectors_map_.end())
490  {
491  it = joint_model_group_map_.find(name);
492  if (it != joint_model_group_map_.end() && it->second->isEndEffector())
493  return it->second;
494  RCLCPP_ERROR(LOGGER, "End-effector '%s' not found in model '%s'", name.c_str(), model_name_.c_str());
495  return nullptr;
496  }
497  return it->second;
498 }
499 
500 bool RobotModel::hasJointModelGroup(const std::string& name) const
501 {
502  return joint_model_group_map_.find(name) != joint_model_group_map_.end();
503 }
504 
505 const JointModelGroup* RobotModel::getJointModelGroup(const std::string& name) const
506 {
507  JointModelGroupMap::const_iterator it = joint_model_group_map_.find(name);
508  if (it == joint_model_group_map_.end())
509  {
510  RCLCPP_ERROR(LOGGER, "Group '%s' not found in model '%s'", name.c_str(), model_name_.c_str());
511  return nullptr;
512  }
513  return it->second;
514 }
515 
517 {
518  JointModelGroupMap::const_iterator it = joint_model_group_map_.find(name);
519  if (it == joint_model_group_map_.end())
520  {
521  RCLCPP_ERROR(LOGGER, "Group '%s' not found in model '%s'", name.c_str(), model_name_.c_str());
522  return nullptr;
523  }
524  return it->second;
525 }
526 
527 void RobotModel::buildGroups(const srdf::Model& srdf_model)
528 {
529  const std::vector<srdf::Model::Group>& group_configs = srdf_model.getGroups();
530 
531  // the only thing tricky is dealing with subgroups
532  std::vector<bool> processed(group_configs.size(), false);
533 
534  bool added = true;
535  while (added)
536  {
537  added = false;
538 
539  // going to make passes until we can't do anything else
540  for (std::size_t i = 0; i < group_configs.size(); ++i)
541  {
542  if (!processed[i])
543  {
544  // if we haven't processed, check and see if the dependencies are met yet
545  bool all_subgroups_added = true;
546  for (const std::string& subgroup : group_configs[i].subgroups_)
547  {
548  if (joint_model_group_map_.find(subgroup) == joint_model_group_map_.end())
549  {
550  all_subgroups_added = false;
551  break;
552  }
553  }
554  if (all_subgroups_added)
555  {
556  added = true;
557  processed[i] = true;
558  if (!addJointModelGroup(group_configs[i]))
559  {
560  RCLCPP_WARN(LOGGER, "Failed to add group '%s'", group_configs[i].name_.c_str());
561  }
562  }
563  }
564  }
565  }
566 
567  for (std::size_t i = 0; i < processed.size(); ++i)
568  {
569  if (!processed[i])
570  {
571  RCLCPP_WARN(LOGGER, "Could not process group '%s' due to unmet subgroup dependencies",
572  group_configs[i].name_.c_str());
573  }
574  }
575 
576  for (JointModelGroupMap::const_iterator it = joint_model_group_map_.begin(); it != joint_model_group_map_.end(); ++it)
577  joint_model_groups_.push_back(it->second);
578  std::sort(joint_model_groups_.begin(), joint_model_groups_.end(), OrderGroupsByName());
579  for (JointModelGroup* joint_model_group : joint_model_groups_)
580  {
581  joint_model_groups_const_.push_back(joint_model_group);
582  joint_model_group_names_.push_back(joint_model_group->getName());
583  }
584 
585  buildGroupsInfoSubgroups();
586  buildGroupsInfoEndEffectors(srdf_model);
587 }
588 
589 void RobotModel::buildGroupsInfoSubgroups()
590 {
591  // compute subgroups
592  for (JointModelGroupMap::const_iterator it = joint_model_group_map_.begin(); it != joint_model_group_map_.end(); ++it)
593  {
594  JointModelGroup* jmg = it->second;
595  std::vector<std::string> subgroup_names;
596  std::set<const JointModel*> joints(jmg->getJointModels().begin(), jmg->getJointModels().end());
597  for (JointModelGroupMap::const_iterator jt = joint_model_group_map_.begin(); jt != joint_model_group_map_.end();
598  ++jt)
599  {
600  if (jt->first != it->first)
601  {
602  bool ok = true;
603  JointModelGroup* sub_jmg = jt->second;
604  const std::vector<const JointModel*>& sub_joints = sub_jmg->getJointModels();
605  for (const JointModel* sub_joint : sub_joints)
606  {
607  if (joints.find(sub_joint) == joints.end())
608  {
609  ok = false;
610  break;
611  }
612  }
613  if (ok)
614  subgroup_names.push_back(sub_jmg->getName());
615  }
616  }
617  if (!subgroup_names.empty())
618  jmg->setSubgroupNames(subgroup_names);
619  }
620 }
621 
622 void RobotModel::buildGroupsInfoEndEffectors(const srdf::Model& srdf_model)
623 {
624  // set the end-effector flags
625  const std::vector<srdf::Model::EndEffector>& eefs = srdf_model.getEndEffectors();
626  for (JointModelGroupMap::const_iterator it = joint_model_group_map_.begin(); it != joint_model_group_map_.end(); ++it)
627  {
628  // check if this group is a known end effector
629  for (const srdf::Model::EndEffector& eef : eefs)
630  {
631  if (eef.component_group_ == it->first)
632  {
633  // if it is, mark it as such
634  it->second->setEndEffectorName(eef.name_);
635  end_effectors_map_[eef.name_] = it->second;
636  end_effectors_.push_back(it->second);
637 
638  // check to see if there are groups that contain the parent link of this end effector.
639  // record this information if found;
640  std::vector<JointModelGroup*> possible_parent_groups;
641  for (JointModelGroupMap::const_iterator jt = joint_model_group_map_.begin(); jt != joint_model_group_map_.end();
642  ++jt)
643  {
644  if (jt->first != it->first)
645  {
646  if (jt->second->hasLinkModel(eef.parent_link_))
647  {
648  jt->second->attachEndEffector(eef.name_);
649  possible_parent_groups.push_back(jt->second);
650  }
651  }
652  }
653 
654  JointModelGroup* eef_parent_group = nullptr;
655  // if a parent group is specified in SRDF, try to use it
656  if (!eef.parent_group_.empty())
657  {
658  JointModelGroupMap::const_iterator jt = joint_model_group_map_.find(eef.parent_group_);
659  if (jt != joint_model_group_map_.end())
660  {
661  if (jt->second->hasLinkModel(eef.parent_link_))
662  {
663  if (jt->second != it->second)
664  {
665  eef_parent_group = jt->second;
666  }
667  else
668  {
669  RCLCPP_ERROR(LOGGER, "Group '%s' for end-effector '%s' cannot be its own parent",
670  eef.parent_group_.c_str(), eef.name_.c_str());
671  }
672  }
673  else
674  {
675  RCLCPP_ERROR(LOGGER,
676  "Group '%s' was specified as parent group for end-effector '%s' "
677  "but it does not include the parent link '%s'",
678  eef.parent_group_.c_str(), eef.name_.c_str(), eef.parent_link_.c_str());
679  }
680  }
681  else
682  {
683  RCLCPP_ERROR(LOGGER, "Group name '%s' not found (specified as parent group for end-effector '%s')",
684  eef.parent_group_.c_str(), eef.name_.c_str());
685  }
686  }
687 
688  // if no parent group was specified, use a default one
689  if (eef_parent_group == nullptr)
690  {
691  if (!possible_parent_groups.empty())
692  {
693  // if there are multiple options for the group that contains this end-effector,
694  // we pick the group with fewest joints.
695  std::size_t best = 0;
696  for (std::size_t g = 1; g < possible_parent_groups.size(); ++g)
697  {
698  if (possible_parent_groups[g]->getJointModels().size() <
699  possible_parent_groups[best]->getJointModels().size())
700  best = g;
701  }
702  eef_parent_group = possible_parent_groups[best];
703  }
704  }
705 
706  if (eef_parent_group)
707  {
708  it->second->setEndEffectorParent(eef_parent_group->getName(), eef.parent_link_);
709  }
710  else
711  {
712  RCLCPP_WARN(LOGGER, "Could not identify parent group for end-effector '%s'", eef.name_.c_str());
713  it->second->setEndEffectorParent("", eef.parent_link_);
714  }
715  }
716  }
717  }
718  std::sort(end_effectors_.begin(), end_effectors_.end(), OrderGroupsByName());
719 }
720 
721 bool RobotModel::addJointModelGroup(const srdf::Model::Group& gc)
722 {
723  if (joint_model_group_map_.find(gc.name_) != joint_model_group_map_.end())
724  {
725  RCLCPP_WARN(LOGGER, "A group named '%s' already exists. Not adding.", gc.name_.c_str());
726  return false;
727  }
728 
729  std::set<const JointModel*> jset;
730 
731  // add joints from chains
732  for (const std::pair<std::string, std::string>& chain : gc.chains_)
733  {
734  const LinkModel* base_link = getLinkModel(chain.first);
735  const LinkModel* tip_link = getLinkModel(chain.second);
736  if (base_link && tip_link)
737  {
738  // go from tip, up the chain, until we hit the root or we find the base_link
739  const LinkModel* lm = tip_link;
740  std::vector<const JointModel*> cj;
741  while (lm)
742  {
743  if (lm == base_link)
744  break;
745  cj.push_back(lm->getParentJointModel());
746  lm = lm->getParentJointModel()->getParentLinkModel();
747  }
748  // if we did not find the base_link, we could have a chain like e.g.,
749  // from one end-effector to another end-effector, so the root is in between
750  if (lm != base_link)
751  {
752  // we go up the chain from the base this time, and see where we intersect the other chain
753  lm = base_link;
754  std::size_t index = 0;
755  std::vector<const JointModel*> cj2;
756  while (lm)
757  {
758  for (std::size_t j = 0; j < cj.size(); ++j)
759  {
760  if (cj[j] == lm->getParentJointModel())
761  {
762  index = j + 1;
763  break;
764  }
765  }
766  if (index > 0)
767  break;
768  cj2.push_back(lm->getParentJointModel());
769  lm = lm->getParentJointModel()->getParentLinkModel();
770  }
771  if (index > 0)
772  {
773  jset.insert(cj.begin(), cj.begin() + index);
774  jset.insert(cj2.begin(), cj2.end());
775  }
776  }
777  else
778  {
779  // if we have a simple chain, just add the joints
780  jset.insert(cj.begin(), cj.end());
781  }
782  }
783  }
784 
785  // add joints
786  for (const std::string& joint : gc.joints_)
787  {
788  const JointModel* j = getJointModel(joint);
789  if (j)
790  jset.insert(j);
791  }
792 
793  // add joints that are parents of included links
794  for (const std::string& link : gc.links_)
795  {
796  const LinkModel* l = getLinkModel(link);
797  if (l)
798  jset.insert(l->getParentJointModel());
799  }
800 
801  // add joints from subgroups
802  for (const std::string& subgroup : gc.subgroups_)
803  {
804  const JointModelGroup* sg = getJointModelGroup(subgroup);
805  if (sg)
806  {
807  // active joints
808  const std::vector<const JointModel*>& js = sg->getJointModels();
809  for (const JointModel* j : js)
810  jset.insert(j);
811 
812  // fixed joints
813  const std::vector<const JointModel*>& fs = sg->getFixedJointModels();
814  for (const JointModel* f : fs)
815  jset.insert(f);
816 
817  // mimic joints
818  const std::vector<const JointModel*>& ms = sg->getMimicJointModels();
819  for (const JointModel* m : ms)
820  jset.insert(m);
821  }
822  }
823 
824  if (jset.empty())
825  {
826  RCLCPP_WARN(LOGGER, "Group '%s' must have at least one valid joint", gc.name_.c_str());
827  return false;
828  }
829 
830  std::vector<const JointModel*> joints;
831  joints.reserve(jset.size());
832  for (const JointModel* it : jset)
833  joints.push_back(it);
834 
835  JointModelGroup* jmg = new JointModelGroup(gc.name_, gc, joints, this);
836  joint_model_group_map_[gc.name_] = jmg;
837 
838  return true;
839 }
840 
841 JointModel* RobotModel::buildRecursive(LinkModel* parent, const urdf::Link* urdf_link, const srdf::Model& srdf_model)
842 {
843  // construct the joint
844  JointModel* joint = constructJointModel(urdf_link, srdf_model);
845 
846  if (joint == nullptr)
847  return nullptr;
848 
849  // bookkeeping for the joint
850  joint_model_vector_.push_back(joint);
851  joint_model_map_[joint->getName()] = joint;
852  joint_model_vector_const_.push_back(joint);
853  joint_model_names_vector_.push_back(joint->getName());
854  joint->setParentLinkModel(parent);
855 
856  // construct the link
857  LinkModel* link = constructLinkModel(urdf_link);
858  joint->setChildLinkModel(link);
859  link->setParentLinkModel(parent);
860 
861  // bookkeeping for the link
862  link_model_map_[joint->getChildLinkModel()->getName()] = link;
863  link_model_vector_.push_back(link);
864  link_model_vector_const_.push_back(link);
865  link_model_names_vector_.push_back(link->getName());
866  if (!link->getShapes().empty())
867  {
869  link_model_names_with_collision_geometry_vector_.push_back(link->getName());
870  link->setFirstCollisionBodyTransformIndex(link_geometry_count_);
871  link_geometry_count_ += link->getShapes().size();
872  }
873  link->setParentJointModel(joint);
874 
875  // recursively build child links (and joints)
876  for (const urdf::LinkSharedPtr& child_link : urdf_link->child_links)
877  {
878  JointModel* jm = buildRecursive(link, child_link.get(), srdf_model);
879  if (jm)
880  link->addChildJointModel(jm);
881  }
882  return joint;
883 }
884 
885 namespace
886 {
887 // construct bounds for 1DOF joint
888 static inline VariableBounds jointBoundsFromURDF(const urdf::Joint* urdf_joint)
889 {
890  VariableBounds b;
891  if (urdf_joint->safety)
892  {
893  b.position_bounded_ = true;
894  b.min_position_ = urdf_joint->safety->soft_lower_limit;
895  b.max_position_ = urdf_joint->safety->soft_upper_limit;
896  if (urdf_joint->limits)
897  {
898  if (urdf_joint->limits->lower > b.min_position_)
899  b.min_position_ = urdf_joint->limits->lower;
900  if (urdf_joint->limits->upper < b.max_position_)
901  b.max_position_ = urdf_joint->limits->upper;
902  }
903  }
904  else
905  {
906  if (urdf_joint->limits)
907  {
908  b.position_bounded_ = true;
909  b.min_position_ = urdf_joint->limits->lower;
910  b.max_position_ = urdf_joint->limits->upper;
911  }
912  }
913  if (urdf_joint->limits)
914  {
915  b.max_velocity_ = fabs(urdf_joint->limits->velocity);
916  b.min_velocity_ = -b.max_velocity_;
917  b.velocity_bounded_ = b.max_velocity_ > std::numeric_limits<double>::epsilon();
918  }
919  return b;
920 }
921 } // namespace
922 
923 JointModel* RobotModel::constructJointModel(const urdf::Link* child_link, const srdf::Model& srdf_model)
924 {
925  JointModel* new_joint_model = nullptr;
926  auto parent_joint = child_link->parent_joint ? child_link->parent_joint.get() : nullptr;
927  auto joint_index = joint_model_vector_.size();
928  auto first_variable_index = joint_model_vector_.empty() ? 0 :
929  joint_model_vector_.back()->getFirstVariableIndex() +
930  joint_model_vector_.back()->getVariableCount();
931 
932  // if parent_joint exists, must be the root link transform
933  if (parent_joint)
934  {
935  switch (parent_joint->type)
936  {
937  case urdf::Joint::REVOLUTE:
938  {
939  RevoluteJointModel* j = new RevoluteJointModel(parent_joint->name, joint_index, first_variable_index);
940  j->setVariableBounds(j->getName(), jointBoundsFromURDF(parent_joint));
941  j->setContinuous(false);
942  j->setAxis(Eigen::Vector3d(parent_joint->axis.x, parent_joint->axis.y, parent_joint->axis.z));
943  new_joint_model = j;
944  }
945  break;
946  case urdf::Joint::CONTINUOUS:
947  {
948  RevoluteJointModel* j = new RevoluteJointModel(parent_joint->name, joint_index, first_variable_index);
949  j->setVariableBounds(j->getName(), jointBoundsFromURDF(parent_joint));
950  j->setContinuous(true);
951  j->setAxis(Eigen::Vector3d(parent_joint->axis.x, parent_joint->axis.y, parent_joint->axis.z));
952  new_joint_model = j;
953  }
954  break;
955  case urdf::Joint::PRISMATIC:
956  {
957  PrismaticJointModel* j = new PrismaticJointModel(parent_joint->name, joint_index, first_variable_index);
958  j->setVariableBounds(j->getName(), jointBoundsFromURDF(parent_joint));
959  j->setAxis(Eigen::Vector3d(parent_joint->axis.x, parent_joint->axis.y, parent_joint->axis.z));
960  new_joint_model = j;
961  }
962  break;
963  case urdf::Joint::FLOATING:
964  new_joint_model = new FloatingJointModel(parent_joint->name, joint_index, first_variable_index);
965  break;
966  case urdf::Joint::PLANAR:
967  new_joint_model = new PlanarJointModel(parent_joint->name, joint_index, first_variable_index);
968  break;
969  case urdf::Joint::FIXED:
970  new_joint_model = new FixedJointModel(parent_joint->name, joint_index, first_variable_index);
971  break;
972  default:
973  RCLCPP_ERROR(LOGGER, "Unknown joint type: %d", static_cast<int>(parent_joint->type));
974  break;
975  }
976  }
977  else // if parent_joint passed in as null, then we're at root of URDF model
978  {
979  const std::vector<srdf::Model::VirtualJoint>& virtual_joints = srdf_model.getVirtualJoints();
980  for (const srdf::Model::VirtualJoint& virtual_joint : virtual_joints)
981  {
982  if (virtual_joint.child_link_ != child_link->name)
983  {
984  if (child_link->name == "world" && virtual_joint.type_ == "fixed" && child_link->collision_array.empty() &&
985  !child_link->collision && child_link->visual_array.empty() && !child_link->visual)
986  {
987  // Gazebo requires a fixed link from a dummy world link to the first robot's link
988  // Skip warning in this case and create a fixed joint with given name
989  new_joint_model = new FixedJointModel(virtual_joint.name_, joint_index, first_variable_index);
990  }
991  else
992  {
993  RCLCPP_WARN(LOGGER,
994  "Skipping virtual joint '%s' because its child frame '%s' "
995  "does not match the URDF frame '%s'",
996  virtual_joint.name_.c_str(), virtual_joint.child_link_.c_str(), child_link->name.c_str());
997  }
998  }
999  else if (virtual_joint.parent_frame_.empty())
1000  {
1001  RCLCPP_WARN(LOGGER, "Skipping virtual joint '%s' because its parent frame is empty",
1002  virtual_joint.name_.c_str());
1003  }
1004  else
1005  {
1006  if (virtual_joint.type_ == "fixed")
1007  {
1008  new_joint_model = new FixedJointModel(virtual_joint.name_, joint_index, first_variable_index);
1009  }
1010  else if (virtual_joint.type_ == "planar")
1011  {
1012  new_joint_model = new PlanarJointModel(virtual_joint.name_, joint_index, first_variable_index);
1013  }
1014  else if (virtual_joint.type_ == "floating")
1015  {
1016  new_joint_model = new FloatingJointModel(virtual_joint.name_, joint_index, first_variable_index);
1017  }
1018  if (new_joint_model)
1019  {
1020  // for fixed frames we still use the robot root link
1021  if (virtual_joint.type_ != "fixed")
1022  {
1023  model_frame_ = virtual_joint.parent_frame_;
1024  }
1025  break;
1026  }
1027  }
1028  }
1029  if (!new_joint_model)
1030  {
1031  RCLCPP_INFO(LOGGER, "No root/virtual joint specified in SRDF. Assuming fixed joint");
1032  new_joint_model = new FixedJointModel("ASSUMED_FIXED_ROOT_JOINT", joint_index, first_variable_index);
1033  }
1034  }
1035 
1036  if (new_joint_model)
1037  {
1038  new_joint_model->setDistanceFactor(new_joint_model->getStateSpaceDimension());
1039  const std::vector<srdf::Model::PassiveJoint>& pjoints = srdf_model.getPassiveJoints();
1040  for (const srdf::Model::PassiveJoint& pjoint : pjoints)
1041  {
1042  if (new_joint_model->getName() == pjoint.name_)
1043  {
1044  new_joint_model->setPassive(true);
1045  break;
1046  }
1047  }
1048 
1049  for (const srdf::Model::JointProperty& property : srdf_model.getJointProperties(new_joint_model->getName()))
1050  {
1051  if (property.property_name_ == "angular_distance_weight")
1052  {
1053  double angular_distance_weight;
1054  try
1055  {
1056  std::string::size_type sz;
1057  angular_distance_weight = std::stod(property.value_, &sz);
1058  if (sz != property.value_.size())
1059  {
1060  RCLCPP_WARN_STREAM(LOGGER, "Extra characters after property " << property.property_name_ << " for joint "
1061  << property.joint_name_ << " as double: '"
1062  << property.value_.substr(sz) << '\'');
1063  }
1064  }
1065  catch (const std::invalid_argument& e)
1066  {
1067  RCLCPP_ERROR_STREAM(LOGGER, "Unable to parse property " << property.property_name_ << " for joint "
1068  << property.joint_name_ << " as double: '"
1069  << property.value_ << '\'');
1070  continue;
1071  }
1072 
1073  if (new_joint_model->getType() == JointModel::JointType::PLANAR)
1074  {
1075  static_cast<PlanarJointModel*>(new_joint_model)->setAngularDistanceWeight(angular_distance_weight);
1076  }
1077  else if (new_joint_model->getType() == JointModel::JointType::FLOATING)
1078  {
1079  static_cast<FloatingJointModel*>(new_joint_model)->setAngularDistanceWeight(angular_distance_weight);
1080  }
1081  else
1082  {
1083  RCLCPP_ERROR_STREAM(LOGGER, "Cannot apply property " << property.property_name_
1084  << " to joint type: " << new_joint_model->getTypeName());
1085  }
1086  }
1087  else if (property.property_name_ == "motion_model")
1088  {
1089  if (new_joint_model->getType() != JointModel::JointType::PLANAR)
1090  {
1091  RCLCPP_ERROR(LOGGER, "Cannot apply property %s to joint type: %s", property.property_name_.c_str(),
1092  new_joint_model->getTypeName().c_str());
1093  continue;
1094  }
1095 
1096  PlanarJointModel::MotionModel motion_model;
1097  if (property.value_ == "holonomic")
1098  {
1099  motion_model = PlanarJointModel::MotionModel::HOLONOMIC;
1100  }
1101  else if (property.value_ == "diff_drive")
1102  {
1103  motion_model = PlanarJointModel::MotionModel::DIFF_DRIVE;
1104  }
1105  else
1106  {
1107  RCLCPP_ERROR_STREAM(LOGGER, "Unknown value for property " << property.property_name_ << " ("
1108  << property.joint_name_ << "): '" << property.value_
1109  << '\'');
1110  RCLCPP_ERROR(LOGGER, "Valid values are 'holonomic' and 'diff_drive'");
1111  continue;
1112  }
1113 
1114  static_cast<PlanarJointModel*>(new_joint_model)->setMotionModel(motion_model);
1115  }
1116  else if (property.property_name_ == "min_translational_distance")
1117  {
1118  if (new_joint_model->getType() != JointModel::JointType::PLANAR)
1119  {
1120  RCLCPP_ERROR(LOGGER, "Cannot apply property %s to joint type: %s", property.property_name_.c_str(),
1121  new_joint_model->getTypeName().c_str());
1122  continue;
1123  }
1124  double min_translational_distance;
1125  try
1126  {
1127  std::string::size_type sz;
1128  min_translational_distance = std::stod(property.value_, &sz);
1129  if (sz != property.value_.size())
1130  {
1131  RCLCPP_WARN_STREAM(LOGGER, "Extra characters after property " << property.property_name_ << " for joint "
1132  << property.joint_name_ << " as double: '"
1133  << property.value_.substr(sz) << '\'');
1134  }
1135  }
1136  catch (const std::invalid_argument& e)
1137  {
1138  RCLCPP_ERROR_STREAM(LOGGER, "Unable to parse property " << property.property_name_ << " for joint "
1139  << property.joint_name_ << " as double: '"
1140  << property.value_ << '\'');
1141  continue;
1142  }
1143 
1144  static_cast<PlanarJointModel*>(new_joint_model)->setMinTranslationalDistance(min_translational_distance);
1145  }
1146  else
1147  {
1148  RCLCPP_ERROR(LOGGER, "Unknown joint property: %s", property.property_name_.c_str());
1149  }
1150  }
1151  }
1152 
1153  return new_joint_model;
1154 }
1155 
1156 namespace
1157 {
1158 static inline Eigen::Isometry3d urdfPose2Isometry3d(const urdf::Pose& pose)
1159 {
1160  Eigen::Quaterniond q(pose.rotation.w, pose.rotation.x, pose.rotation.y, pose.rotation.z);
1161  Eigen::Isometry3d af(Eigen::Translation3d(pose.position.x, pose.position.y, pose.position.z) * q);
1162  return af;
1163 }
1164 } // namespace
1165 
1166 LinkModel* RobotModel::constructLinkModel(const urdf::Link* urdf_link)
1167 {
1168  auto link_index = link_model_vector_.size();
1169  LinkModel* new_link_model = new LinkModel(urdf_link->name, link_index);
1170 
1171  const std::vector<urdf::CollisionSharedPtr>& col_array =
1172  urdf_link->collision_array.empty() ? std::vector<urdf::CollisionSharedPtr>(1, urdf_link->collision) :
1173  urdf_link->collision_array;
1174 
1175  std::vector<shapes::ShapeConstPtr> shapes;
1176  EigenSTL::vector_Isometry3d poses;
1177 
1178  for (const urdf::CollisionSharedPtr& col : col_array)
1179  {
1180  if (col && col->geometry)
1181  {
1182  shapes::ShapeConstPtr s = constructShape(col->geometry.get());
1183  if (s)
1184  {
1185  shapes.push_back(s);
1186  poses.push_back(urdfPose2Isometry3d(col->origin));
1187  }
1188  }
1189  }
1190 
1191  // Should we warn that old (melodic) behaviour has changed, not copying visual to collision geometries anymore?
1192  bool warn_about_missing_collision = false;
1193  if (shapes.empty())
1194  {
1195  const auto& vis_array = urdf_link->visual_array.empty() ? std::vector<urdf::VisualSharedPtr>{ urdf_link->visual } :
1196  urdf_link->visual_array;
1197  for (const urdf::VisualSharedPtr& vis : vis_array)
1198  {
1199  if (vis && vis->geometry)
1200  warn_about_missing_collision = true;
1201  }
1202  }
1203  if (warn_about_missing_collision)
1204  {
1205  RCLCPP_WARN_STREAM(LOGGER, // TODO(henningkayser): use child namespace "empty_collision_geometry"
1206  "Link " << urdf_link->name
1207  << " has visual geometry but no collision geometry. "
1208  "Collision geometry will be left empty. "
1209  "Fix your URDF file by explicitly specifying collision geometry.");
1210  }
1211 
1212  new_link_model->setGeometry(shapes, poses);
1213 
1214  // figure out visual mesh (try visual urdf tag first, collision tag otherwise
1215  if (urdf_link->visual && urdf_link->visual->geometry)
1216  {
1217  if (urdf_link->visual->geometry->type == urdf::Geometry::MESH)
1218  {
1219  const urdf::Mesh* mesh = static_cast<const urdf::Mesh*>(urdf_link->visual->geometry.get());
1220  if (!mesh->filename.empty())
1221  {
1222  new_link_model->setVisualMesh(mesh->filename, urdfPose2Isometry3d(urdf_link->visual->origin),
1223  Eigen::Vector3d(mesh->scale.x, mesh->scale.y, mesh->scale.z));
1224  }
1225  }
1226  }
1227  else if (urdf_link->collision && urdf_link->collision->geometry)
1228  {
1229  if (urdf_link->collision->geometry->type == urdf::Geometry::MESH)
1230  {
1231  const urdf::Mesh* mesh = static_cast<const urdf::Mesh*>(urdf_link->collision->geometry.get());
1232  if (!mesh->filename.empty())
1233  {
1234  new_link_model->setVisualMesh(mesh->filename, urdfPose2Isometry3d(urdf_link->collision->origin),
1235  Eigen::Vector3d(mesh->scale.x, mesh->scale.y, mesh->scale.z));
1236  }
1237  }
1238  }
1239 
1240  if (urdf_link->parent_joint)
1241  {
1242  new_link_model->setJointOriginTransform(
1243  urdfPose2Isometry3d(urdf_link->parent_joint->parent_to_joint_origin_transform));
1244  }
1245 
1246  return new_link_model;
1247 }
1248 
1249 shapes::ShapePtr RobotModel::constructShape(const urdf::Geometry* geom)
1250 {
1251  shapes::Shape* new_shape = nullptr;
1252  switch (geom->type)
1253  {
1254  case urdf::Geometry::SPHERE:
1255  new_shape = new shapes::Sphere(static_cast<const urdf::Sphere*>(geom)->radius);
1256  break;
1257  case urdf::Geometry::BOX:
1258  {
1259  urdf::Vector3 dim = static_cast<const urdf::Box*>(geom)->dim;
1260  new_shape = new shapes::Box(dim.x, dim.y, dim.z);
1261  }
1262  break;
1263  case urdf::Geometry::CYLINDER:
1264  new_shape = new shapes::Cylinder(static_cast<const urdf::Cylinder*>(geom)->radius,
1265  static_cast<const urdf::Cylinder*>(geom)->length);
1266  break;
1267  case urdf::Geometry::MESH:
1268  {
1269  const urdf::Mesh* mesh = static_cast<const urdf::Mesh*>(geom);
1270  if (!mesh->filename.empty())
1271  {
1272  Eigen::Vector3d scale(mesh->scale.x, mesh->scale.y, mesh->scale.z);
1273  shapes::Mesh* m = shapes::createMeshFromResource(mesh->filename, scale);
1274  new_shape = m;
1275  }
1276  }
1277  break;
1278  default:
1279  RCLCPP_ERROR(LOGGER, "Unknown geometry type: %d", static_cast<int>(geom->type));
1280  break;
1281  }
1282 
1283  return shapes::ShapePtr(new_shape);
1284 }
1285 
1286 bool RobotModel::hasJointModel(const std::string& name) const
1287 {
1288  return joint_model_map_.find(name) != joint_model_map_.end();
1289 }
1290 
1291 bool RobotModel::hasLinkModel(const std::string& name) const
1292 {
1293  return link_model_map_.find(name) != link_model_map_.end();
1294 }
1295 
1296 const JointModel* RobotModel::getJointModel(const std::string& name) const
1297 {
1298  JointModelMap::const_iterator it = joint_model_map_.find(name);
1299  if (it != joint_model_map_.end())
1300  return it->second;
1301  RCLCPP_ERROR(LOGGER, "Joint '%s' not found in model '%s'", name.c_str(), model_name_.c_str());
1302  return nullptr;
1303 }
1304 
1305 const JointModel* RobotModel::getJointModel(size_t index) const
1306 {
1307  if (index >= joint_model_vector_.size())
1308  {
1309  RCLCPP_ERROR(LOGGER, "Joint index '%li' out of bounds of joints in model '%s'", index, model_name_.c_str());
1310  return nullptr;
1311  }
1312  assert(joint_model_vector_[index]->getJointIndex() == index);
1313  return joint_model_vector_[index];
1314 }
1315 
1317 {
1318  JointModelMap::const_iterator it = joint_model_map_.find(name);
1319  if (it != joint_model_map_.end())
1320  return it->second;
1321  RCLCPP_ERROR(LOGGER, "Joint '%s' not found in model '%s'", name.c_str(), model_name_.c_str());
1322  return nullptr;
1323 }
1324 
1325 const LinkModel* RobotModel::getLinkModel(const std::string& name, bool* has_link) const
1326 {
1327  return const_cast<RobotModel*>(this)->getLinkModel(name, has_link);
1328 }
1329 
1330 const LinkModel* RobotModel::getLinkModel(size_t index) const
1331 {
1332  if (index >= link_model_vector_.size())
1333  {
1334  RCLCPP_ERROR(LOGGER, "Link index '%li' out of bounds of links in model '%s'", index, model_name_.c_str());
1335  return nullptr;
1336  }
1337  assert(link_model_vector_[index]->getLinkIndex() == index);
1338  return link_model_vector_[index];
1339 }
1340 
1341 LinkModel* RobotModel::getLinkModel(const std::string& name, bool* has_link)
1342 {
1343  if (has_link)
1344  *has_link = true; // Start out optimistic
1345  LinkModelMap::const_iterator it = link_model_map_.find(name);
1346  if (it != link_model_map_.end())
1347  return it->second;
1348 
1349  if (has_link)
1350  {
1351  *has_link = false; // Report failure via argument
1352  }
1353  else
1354  { // Otherwise print error
1355  RCLCPP_ERROR(LOGGER, "Link '%s' not found in model '%s'", name.c_str(), model_name_.c_str());
1356  }
1357  return nullptr;
1358 }
1359 
1361 {
1362  if (!link)
1363  return link;
1364  const moveit::core::LinkModel* parent_link = link->getParentLinkModel();
1365  const moveit::core::JointModel* joint = link->getParentJointModel();
1366 
1367  while (parent_link && joint->getType() == moveit::core::JointModel::FIXED)
1368  {
1369  link = parent_link;
1370  joint = link->getParentJointModel();
1371  parent_link = joint->getParentLinkModel();
1372  }
1373  return link;
1374 }
1375 
1376 void RobotModel::updateMimicJoints(double* values) const
1377 {
1378  for (const JointModel* mimic_joint : mimic_joints_)
1379  {
1380  int src = mimic_joint->getMimic()->getFirstVariableIndex();
1381  int dest = mimic_joint->getFirstVariableIndex();
1382  values[dest] = values[src] * mimic_joint->getMimicFactor() + mimic_joint->getMimicOffset();
1383  }
1384 }
1385 
1386 void RobotModel::getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng, double* values) const
1387 {
1388  for (std::size_t i = 0; i < active_joint_model_vector_.size(); ++i)
1390  updateMimicJoints(values);
1391 }
1392 
1393 void RobotModel::getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng,
1394  std::map<std::string, double>& values) const
1395 {
1396  std::vector<double> tmp(variable_count_);
1397  getVariableRandomPositions(rng, &tmp[0]);
1398  values.clear();
1399  for (std::size_t i = 0; i < variable_names_.size(); ++i)
1400  values[variable_names_[i]] = tmp[i];
1401 }
1402 
1404 {
1405  for (std::size_t i = 0; i < active_joint_model_vector_.size(); ++i)
1407  updateMimicJoints(values);
1408 }
1409 
1410 void RobotModel::getVariableDefaultPositions(std::map<std::string, double>& values) const
1411 {
1412  std::vector<double> tmp(variable_count_);
1413  getVariableDefaultPositions(&tmp[0]);
1414  values.clear();
1415  for (std::size_t i = 0; i < variable_names_.size(); ++i)
1416  values[variable_names_[i]] = tmp[i];
1417 }
1418 
1419 void RobotModel::getMissingVariableNames(const std::vector<std::string>& variables,
1420  std::vector<std::string>& missing_variables) const
1421 {
1422  missing_variables.clear();
1423  std::set<std::string> keys(variables.begin(), variables.end());
1424  for (const std::string& variable_name : variable_names_)
1425  {
1426  if (keys.find(variable_name) == keys.end())
1427  {
1428  if (getJointOfVariable(variable_name)->getMimic() == nullptr)
1429  missing_variables.push_back(variable_name);
1430  }
1431  }
1432 }
1433 
1434 size_t RobotModel::getVariableIndex(const std::string& variable) const
1435 {
1436  VariableIndexMap::const_iterator it = joint_variables_index_map_.find(variable);
1437  if (it == joint_variables_index_map_.end())
1438  throw Exception("Variable '" + variable + "' is not known to model '" + model_name_ + '\'');
1439  return it->second;
1440 }
1441 
1442 double RobotModel::getMaximumExtent(const JointBoundsVector& active_joint_bounds) const
1443 {
1444  double max_distance = 0.0;
1445  for (std::size_t j = 0; j < active_joint_model_vector_.size(); ++j)
1446  {
1447  max_distance += active_joint_model_vector_[j]->getMaximumExtent(*active_joint_bounds[j]) *
1448  active_joint_model_vector_[j]->getDistanceFactor();
1449  }
1450  return max_distance;
1451 }
1452 
1453 bool RobotModel::satisfiesPositionBounds(const double* state, const JointBoundsVector& active_joint_bounds,
1454  double margin) const
1455 {
1456  assert(active_joint_bounds.size() == active_joint_model_vector_.size());
1457  for (std::size_t i = 0; i < active_joint_model_vector_.size(); ++i)
1458  {
1460  *active_joint_bounds[i], margin))
1461  return false;
1462  }
1463  return true;
1464 }
1465 
1466 bool RobotModel::enforcePositionBounds(double* state, const JointBoundsVector& active_joint_bounds) const
1467 {
1468  assert(active_joint_bounds.size() == active_joint_model_vector_.size());
1469  bool change = false;
1470  for (std::size_t i = 0; i < active_joint_model_vector_.size(); ++i)
1471  {
1473  *active_joint_bounds[i]))
1474  change = true;
1475  }
1476  if (change)
1477  updateMimicJoints(state);
1478  return change;
1479 }
1480 
1481 double RobotModel::distance(const double* state1, const double* state2) const
1482 {
1483  double d = 0.0;
1484  for (std::size_t i = 0; i < active_joint_model_vector_.size(); ++i)
1485  {
1486  d += active_joint_model_vector_[i]->getDistanceFactor() *
1488  state2 + active_joint_model_start_index_[i]);
1489  }
1490  return d;
1491 }
1492 
1493 void RobotModel::interpolate(const double* from, const double* to, double t, double* state) const
1494 {
1495  moveit::core::checkInterpolationParamBounds(LOGGER, t);
1496  // we interpolate values only for active joint models (non-mimic)
1497  for (std::size_t i = 0; i < active_joint_model_vector_.size(); ++i)
1498  {
1501  state + active_joint_model_start_index_[i]);
1502  }
1503  // now we update mimic as needed
1504  updateMimicJoints(state);
1505 }
1506 
1507 void RobotModel::setKinematicsAllocators(const std::map<std::string, SolverAllocatorFn>& allocators)
1508 {
1509  // we first set all the "simple" allocators -- where a group has one IK solver
1511  {
1512  std::map<std::string, SolverAllocatorFn>::const_iterator jt = allocators.find(jmg->getName());
1513  if (jt != allocators.end())
1514  {
1515  std::pair<SolverAllocatorFn, SolverAllocatorMapFn> solver_allocator_pair;
1516  solver_allocator_pair.first = jt->second;
1517  jmg->setSolverAllocators(solver_allocator_pair);
1518  }
1519  }
1520 
1521  // now we set compound IK solvers; we do this later because we need the index maps computed by the previous calls to
1522  // setSolverAllocators()
1524  {
1525  std::pair<SolverAllocatorFn, SolverAllocatorMapFn> solver_allocator_pair;
1526  std::map<std::string, SolverAllocatorFn>::const_iterator jt = allocators.find(jmg->getName());
1527  if (jt == allocators.end())
1528  {
1529  // if an kinematics allocator is NOT available for this group, we try to see if we can use subgroups for IK
1530  std::set<const JointModel*> joints;
1531  joints.insert(jmg->getJointModels().begin(), jmg->getJointModels().end());
1532 
1533  std::vector<const JointModelGroup*> subs;
1534 
1535  // go through the groups that have IK allocators and see if they are part of jmg; collect them in subs
1536  for (const std::pair<const std::string, SolverAllocatorFn>& allocator : allocators)
1537  {
1538  const JointModelGroup* sub = getJointModelGroup(allocator.first);
1539  if (!sub) // this should actually not happen, all groups should be well defined
1540  {
1541  subs.clear();
1542  break;
1543  }
1544  std::set<const JointModel*> sub_joints;
1545  sub_joints.insert(sub->getJointModels().begin(), sub->getJointModels().end());
1546 
1547  if (std::includes(joints.begin(), joints.end(), sub_joints.begin(), sub_joints.end()))
1548  { // sub_joints included in joints: add sub, remove sub_joints from joints set
1549  std::set<const JointModel*> joint_model_set;
1550  std::set_difference(joints.begin(), joints.end(), sub_joints.begin(), sub_joints.end(),
1551  std::inserter(joint_model_set, joint_model_set.end()));
1552  // TODO: instead of maintaining disjoint joint sets here,
1553  // should we leave that work to JMG's setSolverAllocators() / computeJointVariableIndices()?
1554  // There, a disjoint bijection from joints to solvers is computed anyway.
1555  // Underlying question: How do we resolve overlaps? Now the first considered sub group "wins"
1556  // But, if the overlap only involves fixed joints, we could consider all sub groups
1557  subs.push_back(sub);
1558  joints.swap(joint_model_set);
1559  }
1560  }
1561 
1562  // if we found subgroups, pass that information to the planning group
1563  if (!subs.empty())
1564  {
1565  std::stringstream ss;
1566  for (const JointModelGroup* sub : subs)
1567  {
1568  ss << sub->getName() << ' ';
1569  solver_allocator_pair.second[sub] = allocators.find(sub->getName())->second;
1570  }
1571  RCLCPP_DEBUG(LOGGER, "Added sub-group IK allocators for group '%s': [ %s]", jmg->getName().c_str(),
1572  ss.str().c_str());
1573  }
1574  jmg->setSolverAllocators(solver_allocator_pair);
1575  }
1576  }
1577 }
1578 
1579 void RobotModel::printModelInfo(std::ostream& out) const
1580 {
1581  out << "Model " << model_name_ << " in frame " << model_frame_ << ", using " << getVariableCount() << " variables\n";
1582 
1583  std::ios_base::fmtflags old_flags = out.flags();
1584  out.setf(std::ios::fixed, std::ios::floatfield);
1585  std::streamsize old_prec = out.precision();
1586  out.precision(5);
1587  out << "Joints: \n";
1588  for (JointModel* joint_model : joint_model_vector_)
1589  {
1590  out << " '" << joint_model->getName() << "' (" << joint_model->getTypeName() << ")\n";
1591  out << " * Joint Index: " << joint_model->getJointIndex() << '\n';
1592  const std::vector<std::string>& vn = joint_model->getVariableNames();
1593  out << " * " << vn.size() << (vn.size() > 1 ? " variables:" : (vn.empty() ? " variables" : " variable:\n"));
1594  int idx = joint_model->getFirstVariableIndex();
1595  for (const std::string& it : vn)
1596  {
1597  out << " * '" << it << "', index " << idx++ << " in full state";
1598  if (joint_model->getMimic())
1599  out << ", mimic '" << joint_model->getMimic()->getName() << '\'';
1600  if (joint_model->isPassive())
1601  out << ", passive";
1602  out << '\n';
1603  out << " " << joint_model->getVariableBounds(it) << '\n';
1604  }
1605  }
1606  out << '\n';
1607  out.precision(old_prec);
1608  out.flags(old_flags);
1609  out << "Links: \n";
1610  for (LinkModel* link_model : link_model_vector_)
1611  {
1612  out << " '" << link_model->getName() << "' with " << link_model->getShapes().size() << " geoms\n";
1613  if (link_model->parentJointIsFixed())
1614  {
1615  out << " * "
1616  << "parent joint is fixed" << '\n';
1617  }
1618  if (link_model->jointOriginTransformIsIdentity())
1619  {
1620  out << " * "
1621  << "joint origin transform is identity\n";
1622  }
1623  }
1624 
1625  out << "Available groups: \n";
1626  for (JointModelGroup* joint_model_group : joint_model_groups_)
1627  joint_model_group->printGroupInfo(out);
1628 }
1629 
1630 void RobotModel::computeFixedTransforms(const LinkModel* link, const Eigen::Isometry3d& transform,
1631  LinkTransformMap& associated_transforms)
1632 {
1633  associated_transforms[link] = transform * link->getJointOriginTransform();
1634  for (std::size_t i = 0; i < link->getChildJointModels().size(); ++i)
1635  {
1636  if (link->getChildJointModels()[i]->getType() == JointModel::FIXED)
1637  {
1638  computeFixedTransforms(link->getChildJointModels()[i]->getChildLinkModel(),
1639  transform * link->getJointOriginTransform(), associated_transforms);
1640  }
1641  }
1642 }
1643 
1644 } // end of namespace core
1645 } // end of namespace moveit
This may be thrown if unrecoverable errors occur.
Definition: exceptions.h:53
const std::vector< const JointModel * > & getJointModels() const
Get all the joints in this group (including fixed and mimic joints).
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
const LinkModel * getParentLinkModel() const
Get the link that this joint connects to. The robot is assumed to start with a joint,...
Definition: joint_model.h:162
const LinkModel * getChildLinkModel() const
Get the link that this joint connects to. There will always be such a link.
Definition: joint_model.h:168
JointType getType() const
Get the type of joint.
Definition: joint_model.h:151
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:72
const JointModel * getParentJointModel() const
Get the joint model whose child this link is. There will always be a parent joint.
Definition: link_model.h:108
const Eigen::Isometry3d & getJointOriginTransform() const
When transforms are computed for this link, they are usually applied to the link's origin....
Definition: link_model.h:143
const LinkModel * getParentLinkModel() const
Get the link model whose child this link is (through some joint). There may not always be a parent li...
Definition: link_model.h:117
const std::vector< const JointModel * > & getChildJointModels() const
A link may have 0 or more child joints. From those joints there will certainly be other descendant li...
Definition: link_model.h:128
MotionModel
different types of planar joints we support
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.h:76
std::size_t link_geometry_count_
Total number of geometric shapes in this model.
Definition: robot_model.h:511
std::size_t getVariableCount() const
Get the number of variables that describe this model.
Definition: robot_model.h:418
std::string model_frame_
The reference (base) frame for this model. The frame is either extracted from the SRDF as a virtual j...
Definition: robot_model.h:481
std::vector< const JointModel * > single_dof_joints_
Definition: robot_model.h:545
std::vector< const JointModel * > joint_model_vector_const_
The vector of joints in the model, in the order they appear in the state vector.
Definition: robot_model.h:525
std::vector< std::string > link_model_names_with_collision_geometry_vector_
The vector of link names that corresponds to link_models_with_collision_geometry_vector_.
Definition: robot_model.h:508
std::vector< std::string > joint_model_group_names_
A vector of all group names, in alphabetical order.
Definition: robot_model.h:595
std::vector< const LinkModel * > link_models_with_collision_geometry_vector_
Only links that have collision geometry specified.
Definition: robot_model.h:505
void updateMimicJoints(double *values) const
Update the variable values for the state of a group with respect to the mimic joints.
bool hasJointModelGroup(const std::string &group) const
Check if the JointModelGroup group exists.
srdf::ModelConstSharedPtr srdf_
Definition: robot_model.h:483
void computeFixedTransforms(const LinkModel *link, const Eigen::Isometry3d &transform, LinkTransformMap &associated_transforms)
Get the transforms between link and all its rigidly attached descendants.
const std::vector< const JointModel * > & getJointModels() const
Get the array of joints, in the order they appear in the robot state.
Definition: robot_model.h:150
std::vector< const LinkModel * > link_model_vector_const_
The vector of links that are updated when computeTransforms() is called, in the order they are update...
Definition: robot_model.h:499
std::vector< std::string > link_model_names_vector_
The vector of link names that corresponds to link_model_vector_.
Definition: robot_model.h:502
std::vector< int > common_joint_roots_
For every two joints, the index of the common root for the joints is stored.
Definition: robot_model.h:556
std::vector< JointModelGroup * > joint_model_groups_
The array of joint model groups, in alphabetical order.
Definition: robot_model.h:589
bool hasEndEffector(const std::string &eef) const
Check if an end effector exists.
void interpolate(const double *from, const double *to, double t, double *state) const
std::vector< JointModel * > joint_model_vector_
The vector of joints in the model, in the order they appear in the state vector.
Definition: robot_model.h:522
std::vector< const JointModel * > mimic_joints_
The set of mimic joints this model contains.
Definition: robot_model.h:543
const LinkModel * getRootLink() const
Get the physical root link of the robot.
Definition: robot_model.cpp:77
const JointModel * getRootJoint() const
Get the root joint. There will be one root joint unless the model is empty. This is either extracted ...
Definition: robot_model.cpp:72
bool hasJointModel(const std::string &name) const
Check if a joint exists. Return true if it does.
size_t getVariableIndex(const std::string &variable) const
Get the index of a variable in the robot state.
~RobotModel()
Destructor. Clear all memory.
Definition: robot_model.cpp:62
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values) const
Compute the random values for a RobotState.
JointBoundsVector active_joint_models_bounds_
The bounds for all the active joint models.
Definition: robot_model.h:575
std::vector< const JointModel * > active_joint_model_vector_const_
The vector of joints in the model, in the order they appear in the state vector.
Definition: robot_model.h:537
std::vector< const JointModel * > joints_of_variable_
The joints that correspond to each variable index.
Definition: robot_model.h:578
LinkModelMap link_model_map_
A map from link names to their instances.
Definition: robot_model.h:493
void getVariableDefaultPositions(double *values) const
Compute the default values for a RobotState.
std::vector< std::string > active_joint_model_names_vector_
The vector of joint names that corresponds to active_joint_model_vector_.
Definition: robot_model.h:534
std::vector< std::string > variable_names_
The names of the DOF that make up this state (this is just a sequence of joint variable names; not ne...
Definition: robot_model.h:562
std::vector< int > active_joint_model_start_index_
Definition: robot_model.h:572
urdf::ModelInterfaceSharedPtr urdf_
Definition: robot_model.h:485
std::vector< const JointModelGroup * > joint_model_groups_const_
The array of joint model groups, in alphabetical order.
Definition: robot_model.h:592
std::vector< LinkModel * > link_model_vector_
The vector of links that are updated when computeTransforms() is called, in the order they are update...
Definition: robot_model.h:496
VariableIndexMap joint_variables_index_map_
The state includes all the joint variables that make up the joints the state consists of....
Definition: robot_model.h:570
const JointModelGroup * getEndEffector(const std::string &name) const
Get the joint group that corresponds to a given end-effector name.
JointModelGroupMap joint_model_group_map_
A map from group names to joint groups.
Definition: robot_model.h:583
std::vector< const JointModelGroup * > end_effectors_
The array of end-effectors, in alphabetical order.
Definition: robot_model.h:598
void getMissingVariableNames(const std::vector< std::string > &variables, std::vector< std::string > &missing_variables) const
RobotModel(const urdf::ModelInterfaceSharedPtr &urdf_model, const srdf::ModelConstSharedPtr &srdf_model)
Construct a kinematic model from a parsed description and a list of planning groups.
Definition: robot_model.cpp:54
std::vector< const JointModel * > multi_dof_joints_
Definition: robot_model.h:547
const JointModelGroup * getJointModelGroup(const std::string &name) const
Get a joint group from this model (by name)
std::vector< const JointModel * > continuous_joint_model_vector_
The set of continuous joints this model contains.
Definition: robot_model.h:540
JointModelGroupMap end_effectors_map_
The known end effectors.
Definition: robot_model.h:586
static const moveit::core::LinkModel * getRigidlyConnectedParentLinkModel(const LinkModel *link)
Get the latest link upwards the kinematic tree, which is only connected via fixed joints.
void printModelInfo(std::ostream &out) const
Print information about the constructed model.
std::vector< std::string > joint_model_names_vector_
The vector of joint names that corresponds to joint_model_vector_.
Definition: robot_model.h:528
double distance(const double *state1, const double *state2) const
Return the sum of joint distances between two states. An L1 norm. Only considers active joints.
const JointModel * getJointOfVariable(int variable_index) const
Definition: robot_model.h:213
bool hasLinkModel(const std::string &name) const
Check if a link exists. Return true if it does.
JointModelMap joint_model_map_
A map from joint names to their instances.
Definition: robot_model.h:519
std::size_t variable_count_
Get the number of variables necessary to describe this model.
Definition: robot_model.h:565
double getMaximumExtent() const
Definition: robot_model.h:350
std::string model_name_
The name of the robot.
Definition: robot_model.h:477
const LinkModel * root_link_
The first physical link for the robot.
Definition: robot_model.h:490
const LinkModel * getLinkModel(const std::string &link, bool *has_link=nullptr) const
Get a link by its name. Output error and return nullptr when the link is missing.
bool satisfiesPositionBounds(const double *state, double margin=0.0) const
Definition: robot_model.h:344
std::vector< JointModel * > active_joint_model_vector_
The vector of joints in the model, in the order they appear in the state vector.
Definition: robot_model.h:531
void setKinematicsAllocators(const std::map< std::string, SolverAllocatorFn > &allocators)
A map of known kinematics solvers (associated to their group name)
const JointModel * getJointModel(const std::string &joint) const
Get a joint by its name. Output error and return nullptr when the joint is missing.
const JointModel * root_joint_
The root joint.
Definition: robot_model.h:516
const std::string & getName() const
Get the model name.
Definition: robot_model.h:85
bool enforcePositionBounds(double *state) const
Definition: robot_model.h:339
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
std::map< const LinkModel *, Eigen::Isometry3d, std::less< const LinkModel * >, Eigen::aligned_allocator< std::pair< const LinkModel *const, Eigen::Isometry3d > > > LinkTransformMap
Map from link model instances to Eigen transforms.
Definition: link_model.h:68
std::vector< const JointModel::Bounds * > JointBoundsVector
Main namespace for MoveIt.
Definition: exceptions.h:43
d
Definition: setup.py:4
name
Definition: setup.py:7
Definition: world.h:49
FilterFn chain(const std::vector< FilterFn > &filter_functions)