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