moveit2
The MoveIt Motion Planning Framework for ROS 2.
joint_model_group.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, Dave Coleman */
37 
42 #include <rclcpp/logger.hpp>
43 #include <rclcpp/logging.hpp>
44 #include <algorithm>
45 
47 
48 namespace moveit
49 {
50 namespace core
51 {
52 namespace
53 {
54 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_robot_model.joint_model_group");
55 
56 // check if a parent or ancestor of joint is included in this group
57 bool includesParent(const JointModel* joint, const JointModelGroup* group)
58 {
59  bool found = false;
60  // if we find that an ancestor is also in the group, then the joint is not a root
61  while (joint->getParentLinkModel() != nullptr)
62  {
63  joint = joint->getParentLinkModel()->getParentJointModel();
64  if (group->hasJointModel(joint->getName()) && joint->getVariableCount() > 0 && joint->getMimic() == nullptr)
65  {
66  found = true;
67  break;
68  }
69  else if (joint->getMimic() != nullptr)
70  {
71  const JointModel* mjoint = joint->getMimic();
72  if (group->hasJointModel(mjoint->getName()) && mjoint->getVariableCount() > 0 && mjoint->getMimic() == nullptr)
73  found = true;
74  else if (includesParent(mjoint, group))
75  found = true;
76  if (found)
77  break;
78  }
79  }
80  return found;
81 }
82 
83 // check if joint a is right below b, in the kinematic chain, with no active DOF missing
84 bool jointPrecedes(const JointModel* a, const JointModel* b)
85 {
86  if (!a->getParentLinkModel())
87  return false;
88  const JointModel* p = a->getParentLinkModel()->getParentJointModel();
89  while (p)
90  {
91  if (p == b)
92  return true;
93  if (p->getType() == JointModel::FIXED)
94  p = p->getParentLinkModel() ? p->getParentLinkModel()->getParentJointModel() : nullptr;
95  else
96  break;
97  }
98 
99  return false;
100 }
101 } // namespace
102 
103 JointModelGroup::JointModelGroup(const std::string& group_name, const srdf::Model::Group& config,
104  const std::vector<const JointModel*>& unsorted_group_joints,
105  const RobotModel* parent_model)
106  : parent_model_(parent_model)
107  , name_(group_name)
108  , common_root_(nullptr)
109  , variable_count_(0)
110  , active_variable_count_(0)
111  , is_contiguous_index_list_(true)
112  , is_chain_(false)
113  , is_single_dof_(true)
114  , config_(config)
115 {
116  // sort joints in Depth-First order
117  joint_model_vector_ = unsorted_group_joints;
118  std::sort(joint_model_vector_.begin(), joint_model_vector_.end(), OrderJointsByIndex());
120 
121  // figure out active joints, mimic joints, fixed joints
122  // construct index maps, list of variables
123  for (const JointModel* joint_model : joint_model_vector_)
124  {
125  joint_model_name_vector_.push_back(joint_model->getName());
126  joint_model_map_[joint_model->getName()] = joint_model;
127  unsigned int vc = joint_model->getVariableCount();
128  if (vc > 0)
129  {
130  if (vc > 1)
131  is_single_dof_ = false;
132  const std::vector<std::string>& name_order = joint_model->getVariableNames();
133  if (joint_model->getMimic() == nullptr)
134  {
135  active_joint_model_vector_.push_back(joint_model);
136  active_joint_model_name_vector_.push_back(joint_model->getName());
138  active_joint_models_bounds_.push_back(&joint_model->getVariableBounds());
140  }
141  else
142  mimic_joints_.push_back(joint_model);
143  for (const std::string& name : name_order)
144  {
145  variable_names_.push_back(name);
146  variable_names_set_.insert(name);
147  }
148 
149  int first_index = joint_model->getFirstVariableIndex();
150  for (std::size_t j = 0; j < name_order.size(); ++j)
151  {
152  variable_index_list_.push_back(first_index + j);
153  joint_variables_index_map_[name_order[j]] = variable_count_ + j;
154  }
155  joint_variables_index_map_[joint_model->getName()] = variable_count_;
156 
157  if (joint_model->getType() == JointModel::REVOLUTE &&
158  static_cast<const RevoluteJointModel*>(joint_model)->isContinuous())
159  continuous_joint_model_vector_.push_back(joint_model);
160 
161  variable_count_ += vc;
162  }
163  else
164  fixed_joints_.push_back(joint_model);
165  }
166 
167  // now we need to find all the set of joints within this group
168  // that root distinct subtrees
169  for (const JointModel* active_joint_model : active_joint_model_vector_)
170  {
171  // if we find that an ancestor is also in the group, then the joint is not a root
172  if (!includesParent(active_joint_model, this))
173  joint_roots_.push_back(active_joint_model);
174  }
175 
176  // when updating this group within a state, it is useful to know
177  // if the full state of a group is contiguous within the full state of the robot
178  if (variable_index_list_.empty())
180  else
181  for (std::size_t i = 1; i < variable_index_list_.size(); ++i)
182  if (variable_index_list_[i] != variable_index_list_[i - 1] + 1)
183  {
185  break;
186  }
187 
188  // when updating/sampling a group state only, only mimic joints that have their parent within the group get updated.
189  for (const JointModel* mimic_joint : mimic_joints_)
190  // if the joint we mimic is also in this group, we will need to do updates when sampling
191  if (hasJointModel(mimic_joint->getMimic()->getName()))
192  {
193  int src = joint_variables_index_map_[mimic_joint->getMimic()->getName()];
194  int dest = joint_variables_index_map_[mimic_joint->getName()];
195  GroupMimicUpdate mu(src, dest, mimic_joint->getMimicFactor(), mimic_joint->getMimicOffset());
196  group_mimic_update_.push_back(mu);
197  }
198 
199  // now we need to make another pass for group links (we include the fixed joints here)
200  std::set<const LinkModel*> group_links_set;
201  for (const JointModel* joint_model : joint_model_vector_)
202  group_links_set.insert(joint_model->getChildLinkModel());
203  for (const LinkModel* group_link : group_links_set)
204  link_model_vector_.push_back(group_link);
205  std::sort(link_model_vector_.begin(), link_model_vector_.end(), OrderLinksByIndex());
206 
207  for (const LinkModel* link_model : link_model_vector_)
208  {
209  link_model_map_[link_model->getName()] = link_model;
210  link_model_name_vector_.push_back(link_model->getName());
211  if (!link_model->getShapes().empty())
212  {
213  link_model_with_geometry_vector_.push_back(link_model);
214  link_model_with_geometry_name_vector_.push_back(link_model->getName());
215  }
216  }
217 
218  // compute the common root of this group
219  if (!joint_roots_.empty())
220  {
222  for (std::size_t i = 1; i < joint_roots_.size(); ++i)
224  }
225 
226  // compute updated links
227  for (const JointModel* joint_root : joint_roots_)
228  {
229  const std::vector<const LinkModel*>& links = joint_root->getDescendantLinkModels();
230  updated_link_model_set_.insert(links.begin(), links.end());
231  }
232  for (const LinkModel* updated_link_model : updated_link_model_set_)
233  {
234  updated_link_model_name_set_.insert(updated_link_model->getName());
235  updated_link_model_vector_.push_back(updated_link_model);
236  if (!updated_link_model->getShapes().empty())
237  {
238  updated_link_model_with_geometry_vector_.push_back(updated_link_model);
239  updated_link_model_with_geometry_set_.insert(updated_link_model);
240  updated_link_model_with_geometry_name_set_.insert(updated_link_model->getName());
241  }
242  }
243  std::sort(updated_link_model_vector_.begin(), updated_link_model_vector_.end(), OrderLinksByIndex());
245  OrderLinksByIndex());
246  for (const LinkModel* updated_link_model : updated_link_model_vector_)
247  updated_link_model_name_vector_.push_back(updated_link_model->getName());
248  for (const LinkModel* updated_link_model_with_geometry : updated_link_model_with_geometry_vector_)
249  updated_link_model_with_geometry_name_vector_.push_back(updated_link_model_with_geometry->getName());
250 
251  // check if this group should actually be a chain
252  if (joint_roots_.size() == 1 && !active_joint_model_vector_.empty())
253  {
254  bool chain = true;
255  // due to our sorting, the joints are sorted in a DF fashion, so looking at them in reverse,
256  // we should always get to the parent.
257  for (std::size_t k = joint_model_vector_.size() - 1; k > 0; --k)
258  if (!jointPrecedes(joint_model_vector_[k], joint_model_vector_[k - 1]))
259  {
260  chain = false;
261  break;
262  }
263  if (chain)
264  is_chain_ = true;
265  }
266 }
267 
269 
270 void JointModelGroup::setSubgroupNames(const std::vector<std::string>& subgroups)
271 {
272  subgroup_names_ = subgroups;
273  subgroup_names_set_.clear();
274  for (const std::string& subgroup_name : subgroup_names_)
275  subgroup_names_set_.insert(subgroup_name);
276 }
277 
278 void JointModelGroup::getSubgroups(std::vector<const JointModelGroup*>& sub_groups) const
279 {
280  sub_groups.resize(subgroup_names_.size());
281  for (std::size_t i = 0; i < subgroup_names_.size(); ++i)
282  sub_groups[i] = parent_model_->getJointModelGroup(subgroup_names_[i]);
283 }
284 
285 bool JointModelGroup::hasJointModel(const std::string& joint) const
286 {
287  return joint_model_map_.find(joint) != joint_model_map_.end();
288 }
289 
290 bool JointModelGroup::hasLinkModel(const std::string& link) const
291 {
292  return link_model_map_.find(link) != link_model_map_.end();
293 }
294 
295 const LinkModel* JointModelGroup::getLinkModel(const std::string& name) const
296 {
297  LinkModelMapConst::const_iterator it = link_model_map_.find(name);
298  if (it == link_model_map_.end())
299  {
300  RCLCPP_ERROR(LOGGER, "Link '%s' not found in group '%s'", name.c_str(), name_.c_str());
301  return nullptr;
302  }
303  return it->second;
304 }
305 
306 const JointModel* JointModelGroup::getJointModel(const std::string& name) const
307 {
308  JointModelMapConst::const_iterator it = joint_model_map_.find(name);
309  if (it == joint_model_map_.end())
310  {
311  RCLCPP_ERROR(LOGGER, "Joint '%s' not found in group '%s'", name.c_str(), name_.c_str());
312  return nullptr;
313  }
314  return it->second;
315 }
316 
317 void JointModelGroup::getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng, double* values,
318  const JointBoundsVector& active_joint_bounds) const
319 {
320  assert(active_joint_bounds.size() == active_joint_model_vector_.size());
321  for (std::size_t i = 0; i < active_joint_model_vector_.size(); ++i)
323  *active_joint_bounds[i]);
324 
325  updateMimicJoints(values);
326 }
327 
328 void JointModelGroup::getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator& rng, double* values,
329  const JointBoundsVector& active_joint_bounds, const double* near,
330  double distance) const
331 {
332  assert(active_joint_bounds.size() == active_joint_model_vector_.size());
333  for (std::size_t i = 0; i < active_joint_model_vector_.size(); ++i)
335  *active_joint_bounds[i],
337  distance);
338  updateMimicJoints(values);
339 }
340 
341 void JointModelGroup::getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator& rng, double* values,
342  const JointBoundsVector& active_joint_bounds, const double* near,
343  const std::map<JointModel::JointType, double>& distance_map) const
344 {
345  assert(active_joint_bounds.size() == active_joint_model_vector_.size());
346  for (std::size_t i = 0; i < active_joint_model_vector_.size(); ++i)
347  {
348  double distance = 0.0;
349  std::map<JointModel::JointType, double>::const_iterator iter =
350  distance_map.find(active_joint_model_vector_[i]->getType());
351  if (iter != distance_map.end())
352  distance = iter->second;
353  else
354  {
355  RCLCPP_WARN(LOGGER, "Did not pass in distance for '%s'", active_joint_model_vector_[i]->getName().c_str());
356  }
357  active_joint_model_vector_[i]->getVariableRandomPositionsNearBy(rng, values + active_joint_model_start_index_[i],
358  *active_joint_bounds[i],
360  distance);
361  }
362  updateMimicJoints(values);
363 }
364 
365 void JointModelGroup::getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator& rng, double* values,
366  const JointBoundsVector& active_joint_bounds, const double* near,
367  const std::vector<double>& distances) const
368 {
369  assert(active_joint_bounds.size() == active_joint_model_vector_.size());
370  if (distances.size() != active_joint_model_vector_.size())
371  throw Exception("When sampling random values nearby for group '" + name_ +
372  "', distances vector should be of size " + std::to_string(active_joint_model_vector_.size()) +
373  ", but it is of size " + std::to_string(distances.size()));
374  for (std::size_t i = 0; i < active_joint_model_vector_.size(); ++i)
376  *active_joint_bounds[i],
378  distances[i]);
379  updateMimicJoints(values);
380 }
381 
382 bool JointModelGroup::satisfiesPositionBounds(const double* state, const JointBoundsVector& active_joint_bounds,
383  double margin) const
384 {
385  assert(active_joint_bounds.size() == active_joint_model_vector_.size());
386  for (std::size_t i = 0; i < active_joint_model_vector_.size(); ++i)
388  *active_joint_bounds[i], margin))
389  return false;
390  return true;
391 }
392 
393 bool JointModelGroup::enforcePositionBounds(double* state, const JointBoundsVector& active_joint_bounds) const
394 {
395  assert(active_joint_bounds.size() == active_joint_model_vector_.size());
396  bool change = false;
397  for (std::size_t i = 0; i < active_joint_model_vector_.size(); ++i)
399  *active_joint_bounds[i]))
400  change = true;
401  if (change)
402  updateMimicJoints(state);
403  return change;
404 }
405 
406 double JointModelGroup::getMaximumExtent(const JointBoundsVector& active_joint_bounds) const
407 {
408  double max_distance = 0.0;
409  for (std::size_t j = 0; j < active_joint_model_vector_.size(); ++j)
410  max_distance += active_joint_model_vector_[j]->getMaximumExtent(*active_joint_bounds[j]) *
411  active_joint_model_vector_[j]->getDistanceFactor();
412  return max_distance;
413 }
414 
415 double JointModelGroup::distance(const double* state1, const double* state2) const
416 {
417  double d = 0.0;
418  for (std::size_t i = 0; i < active_joint_model_vector_.size(); ++i)
419  d += active_joint_model_vector_[i]->getDistanceFactor() *
421  state2 + active_joint_model_start_index_[i]);
422  return d;
423 }
424 
425 void JointModelGroup::interpolate(const double* from, const double* to, double t, double* state) const
426 {
427  // we interpolate values only for active joint models (non-mimic)
428  for (std::size_t i = 0; i < active_joint_model_vector_.size(); ++i)
432 
433  // now we update mimic as needed
434  updateMimicJoints(state);
435 }
436 
437 void JointModelGroup::updateMimicJoints(double* values) const
438 {
439  // update mimic (only local joints as we are dealing with a local group state)
440  for (const GroupMimicUpdate& mimic_update : group_mimic_update_)
441  values[mimic_update.dest] = values[mimic_update.src] * mimic_update.factor + mimic_update.offset;
442 }
443 
444 void JointModelGroup::addDefaultState(const std::string& name, const std::map<std::string, double>& default_state)
445 {
446  default_states_[name] = default_state;
447  default_states_names_.push_back(name);
448 }
449 
450 bool JointModelGroup::getVariableDefaultPositions(const std::string& name, std::map<std::string, double>& values) const
451 {
452  std::map<std::string, std::map<std::string, double> >::const_iterator it = default_states_.find(name);
453  if (it == default_states_.end())
454  return false;
455  values = it->second;
456  return true;
457 }
458 
460 {
461  for (std::size_t i = 0; i < active_joint_model_vector_.size(); ++i)
463  updateMimicJoints(values);
464 }
465 
466 void JointModelGroup::getVariableDefaultPositions(std::map<std::string, double>& values) const
467 {
468  std::vector<double> tmp(variable_count_);
470  for (std::size_t i = 0; i < variable_names_.size(); ++i)
471  values[variable_names_[i]] = tmp[i];
472 }
473 
475 {
477 }
478 
479 void JointModelGroup::setEndEffectorParent(const std::string& group, const std::string& link)
480 {
481  end_effector_parent_.first = group;
482  end_effector_parent_.second = link;
483 }
484 
485 void JointModelGroup::attachEndEffector(const std::string& eef_name)
486 {
487  attached_end_effector_names_.push_back(eef_name);
488 }
489 
490 bool JointModelGroup::getEndEffectorTips(std::vector<std::string>& tips) const
491 {
492  // Get a vector of tip links
493  std::vector<const LinkModel*> tip_links;
494  if (!getEndEffectorTips(tip_links))
495  return false;
496 
497  // Convert to string names
498  tips.clear();
499  for (const LinkModel* link_model : tip_links)
500  tips.push_back(link_model->getName());
501  return true;
502 }
503 
504 bool JointModelGroup::getEndEffectorTips(std::vector<const LinkModel*>& tips) const
505 {
506  tips.clear();
507  for (const std::string& name : getAttachedEndEffectorNames())
508  {
510  if (!eef)
511  {
512  RCLCPP_ERROR(LOGGER, "Unable to find joint model group for eef");
513  return false;
514  }
515  const std::string& eef_parent = eef->getEndEffectorParentGroup().second;
516 
517  const LinkModel* eef_link = parent_model_->getLinkModel(eef_parent);
518  if (!eef_link)
519  {
520  RCLCPP_ERROR(LOGGER, "Unable to find end effector link for eef");
521  return false;
522  }
523  // insert eef_link into tips, maintaining a *sorted* vector, thus enabling use of std::lower_bound
524  const auto insert_it = std::lower_bound(tips.cbegin(), tips.cend(), eef_link);
525  if (insert_it == tips.end() || eef_link != *insert_it) // only insert if not a duplicate
526  tips.insert(insert_it, eef_link);
527  }
528  return true;
529 }
530 
532 {
533  std::vector<const LinkModel*> tips;
534  getEndEffectorTips(tips);
535  if (tips.size() == 1)
536  return tips.front();
537  else if (tips.size() > 1)
538  {
539  RCLCPP_ERROR(LOGGER, "More than one end effector tip found for joint model group, so cannot return only one");
540  }
541  else
542  {
543  RCLCPP_ERROR(LOGGER, "No end effector tips found in joint model group");
544  }
545  return nullptr;
546 }
547 
548 int JointModelGroup::getVariableGroupIndex(const std::string& variable) const
549 {
550  VariableIndexMap::const_iterator it = joint_variables_index_map_.find(variable);
551  if (it == joint_variables_index_map_.end())
552  {
553  RCLCPP_ERROR(LOGGER, "Variable '%s' is not part of group '%s'", variable.c_str(), name_.c_str());
554  return -1;
555  }
556  return it->second;
557 }
558 
560 {
561  group_kinematics_.first.default_ik_timeout_ = ik_timeout;
562  if (group_kinematics_.first.solver_instance_)
563  group_kinematics_.first.solver_instance_->setDefaultTimeout(ik_timeout);
564  for (std::pair<const JointModelGroup* const, KinematicsSolver>& it : group_kinematics_.second)
565  it.second.default_ik_timeout_ = ik_timeout;
566 }
567 
568 bool JointModelGroup::computeIKIndexBijection(const std::vector<std::string>& ik_jnames,
569  std::vector<size_t>& joint_bijection) const
570 {
571  joint_bijection.clear();
572  for (const std::string& ik_jname : ik_jnames)
573  {
574  VariableIndexMap::const_iterator it = joint_variables_index_map_.find(ik_jname);
575  if (it == joint_variables_index_map_.end())
576  {
577  // skip reported fixed joints
578  if (hasJointModel(ik_jname) && getJointModel(ik_jname)->getType() == JointModel::FIXED)
579  continue;
580  RCLCPP_ERROR(LOGGER,
581  "IK solver computes joint values for joint '%s' "
582  "but group '%s' does not contain such a joint.",
583  ik_jname.c_str(), getName().c_str());
584  return false;
585  }
586  const JointModel* jm = getJointModel(ik_jname);
587  for (size_t k = 0; k < jm->getVariableCount(); ++k)
588  joint_bijection.push_back(it->second + k);
589  }
590  return true;
591 }
592 
593 void JointModelGroup::setSolverAllocators(const std::pair<SolverAllocatorFn, SolverAllocatorMapFn>& solvers)
594 {
595  if (solvers.first)
596  {
597  group_kinematics_.first.allocator_ = solvers.first;
598  group_kinematics_.first.solver_instance_ = solvers.first(this);
599  if (group_kinematics_.first.solver_instance_)
600  {
601  group_kinematics_.first.solver_instance_->setDefaultTimeout(group_kinematics_.first.default_ik_timeout_);
602  if (!computeIKIndexBijection(group_kinematics_.first.solver_instance_->getJointNames(),
603  group_kinematics_.first.bijection_))
604  group_kinematics_.first.reset();
605  }
606  }
607  else
608  // we now compute a joint bijection only if we have a solver map
609  for (const std::pair<const JointModelGroup* const, SolverAllocatorFn>& it : solvers.second)
610  if (it.first->getSolverInstance())
611  {
612  KinematicsSolver& ks = group_kinematics_.second[it.first];
613  ks.allocator_ = it.second;
614  ks.solver_instance_ = const_cast<JointModelGroup*>(it.first)->getSolverInstance();
615  ks.default_ik_timeout_ = group_kinematics_.first.default_ik_timeout_;
616  if (!computeIKIndexBijection(ks.solver_instance_->getJointNames(), ks.bijection_))
617  {
618  group_kinematics_.second.clear();
619  break;
620  }
621  }
622 }
623 
624 bool JointModelGroup::canSetStateFromIK(const std::string& tip) const
625 {
626  const kinematics::KinematicsBaseConstPtr& solver = getSolverInstance();
627  if (!solver || tip.empty())
628  return false;
629 
630  const std::vector<std::string>& tip_frames = solver->getTipFrames();
631 
632  if (tip_frames.empty())
633  {
634  RCLCPP_WARN(LOGGER, "Group %s has no tip frame(s)", name_.c_str());
635  return false;
636  }
637 
638  // loop through all tip frames supported by the JMG
639  for (const std::string& tip_frame : tip_frames)
640  {
641  // remove frame reference, if specified
642  const std::string& tip_local = tip[0] == '/' ? tip.substr(1) : tip;
643  const std::string& tip_frame_local = tip_frame[0] == '/' ? tip_frame.substr(1) : tip_frame;
644  RCLCPP_DEBUG(LOGGER, "comparing input tip: %s to this groups tip: %s ", tip_local.c_str(), tip_frame_local.c_str());
645 
646  // Check if the IK solver's tip is the same as the frame of inquiry
647  if (tip_local != tip_frame_local)
648  {
649  // If not the same, check if this planning group includes the frame of inquiry
650  if (hasLinkModel(tip_frame_local))
651  {
652  const LinkModel* lm = getLinkModel(tip_frame_local);
653  const LinkTransformMap& fixed_links = lm->getAssociatedFixedTransforms();
654  // Check if our frame of inquiry is located anywhere further down the chain (towards the tip of the arm)
655  for (const std::pair<const LinkModel* const, Eigen::Isometry3d>& fixed_link : fixed_links)
656  {
657  if (fixed_link.first->getName() == tip_local)
658  return true;
659  }
660  }
661  }
662  else
663  return true;
664  }
665 
666  // Did not find any valid tip frame links to use
667  return false;
668 }
669 
670 void JointModelGroup::printGroupInfo(std::ostream& out) const
671 {
672  out << "Group '" << name_ << "' using " << variable_count_ << " variables\n";
673  out << " * Joints:\n";
674  for (const JointModel* joint_model : joint_model_vector_)
675  out << " '" << joint_model->getName() << "' (" << joint_model->getTypeName() << ")\n";
676  out << " * Variables:\n";
677  for (const std::string& variable_name : variable_names_)
678  {
679  int local_idx = joint_variables_index_map_.find(variable_name)->second;
680  const JointModel* jm = parent_model_->getJointOfVariable(variable_name);
681  out << " '" << variable_name << "', index "
682  << (jm->getFirstVariableIndex() + jm->getLocalVariableIndex(variable_name)) << " in full state, index "
683  << local_idx << " in group state";
684  if (jm->getMimic())
685  out << ", mimic '" << jm->getMimic()->getName() << "'";
686  out << '\n';
687  out << " " << parent_model_->getVariableBounds(variable_name) << '\n';
688  }
689  out << " * Variables Index List:\n";
690  out << " ";
691  for (int variable_index : variable_index_list_)
692  out << variable_index << " ";
694  out << "(contiguous)";
695  else
696  out << "(non-contiguous)";
697  out << '\n';
698  if (group_kinematics_.first)
699  {
700  out << " * Kinematics solver bijection:\n";
701  out << " ";
702  for (unsigned int index : group_kinematics_.first.bijection_)
703  out << index << " ";
704  out << '\n';
705  }
706  if (!group_kinematics_.second.empty())
707  {
708  out << " * Compound kinematics solver:\n";
709  for (const std::pair<const JointModelGroup* const, KinematicsSolver>& it : group_kinematics_.second)
710  {
711  out << " " << it.first->getName() << ":";
712  for (unsigned int index : it.second.bijection_)
713  out << " " << index;
714  out << '\n';
715  }
716  }
717 
718  if (!group_mimic_update_.empty())
719  {
720  out << " * Local Mimic Updates:\n";
721  for (const GroupMimicUpdate& mimic_update : group_mimic_update_)
722  out << " [" << mimic_update.dest << "] = " << mimic_update.factor << " * [" << mimic_update.src << "] + "
723  << mimic_update.offset << '\n';
724  }
725  out << '\n';
726 }
727 
728 bool JointModelGroup::isValidVelocityMove(const std::vector<double>& from_joint_pose,
729  const std::vector<double>& to_joint_pose, double dt) const
730 {
731  // Check for equal sized arrays
732  if (from_joint_pose.size() != to_joint_pose.size())
733  {
734  RCLCPP_ERROR(LOGGER, "To and from joint poses are of different sizes.");
735  return false;
736  }
737 
738  return isValidVelocityMove(&from_joint_pose[0], &to_joint_pose[0], from_joint_pose.size(), dt);
739 }
740 
741 bool JointModelGroup::isValidVelocityMove(const double* from_joint_pose, const double* to_joint_pose,
742  std::size_t array_size, double dt) const
743 {
744  const std::vector<const JointModel::Bounds*>& bounds = getActiveJointModelsBounds();
745  const std::vector<size_t>& bij = getKinematicsSolverJointBijection();
746 
747  for (std::size_t i = 0; i < array_size; ++i)
748  {
749  double dtheta = std::abs(from_joint_pose[i] - to_joint_pose[i]);
750  const std::vector<moveit::core::VariableBounds>* var_bounds = bounds[bij[i]];
751 
752  if (var_bounds->size() != 1)
753  {
754  // TODO(davetcoleman) Support multiple variables
755  RCLCPP_ERROR(LOGGER, "Attempting to check velocity bounds for waypoint move with joints that have multiple "
756  "variables");
757  return false;
758  }
759  const double max_velocity = (*var_bounds)[0].max_velocity_;
760 
761  double max_dtheta = dt * max_velocity;
762  if (dtheta > max_dtheta)
763  {
764  RCLCPP_DEBUG(LOGGER, "Not valid velocity move because of joint %lu", i);
765  return false;
766  }
767  }
768 
769  return true;
770 }
771 } // end of namespace core
772 } // end of namespace moveit
This may be thrown if unrecoverable errors occur.
Definition: exceptions.h:53
std::set< const LinkModel * > updated_link_model_with_geometry_set_
The list of downstream link models in the order they should be updated (may include links that are no...
std::vector< int > variable_index_list_
The list of index values this group includes, with respect to a full robot state; this includes mimic...
std::string name_
Name of group.
std::vector< const JointModel * > joint_model_vector_
Joint instances in the order they appear in the group state.
bool is_contiguous_index_list_
True if the state of this group is contiguous within the full robot state; this also means that the i...
std::vector< const JointModel * > continuous_joint_model_vector_
The set of continuous joints this group contains.
bool getEndEffectorTips(std::vector< const LinkModel * > &tips) const
Get the unique set of end effector tips included in a particular joint model group as defined by the ...
std::vector< const JointModel * > active_joint_model_vector_
Active joint instances in the order they appear in the group state.
std::vector< const JointModel * > joint_roots_
The list of active joint models that are roots in this group.
void setDefaultIKTimeout(double ik_timeout)
Set the default IK timeout.
std::vector< const LinkModel * > link_model_vector_
The links that are on the direct lineage between joints and joint_roots_, as well as the children of ...
std::vector< const LinkModel * > updated_link_model_with_geometry_vector_
The list of downstream link models in the order they should be updated (may include links that are no...
const std::string & getName() const
Get the name of the joint group.
std::map< std::string, std::map< std::string, double > > default_states_
The set of default states specified for this group in the SRDF.
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values) const
Compute random values for the state of the joint group.
std::vector< std::string > updated_link_model_name_vector_
The list of downstream link names in the order they should be updated (may include links that are not...
double distance(const double *state1, const double *state2) const
void getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const double *near, const double distance) const
Compute random values for the state of the joint group.
void attachEndEffector(const std::string &eef_name)
Notify this group that there is an end-effector attached to it.
void setSolverAllocators(const SolverAllocatorFn &solver, const SolverAllocatorMapFn &solver_map=SolverAllocatorMapFn())
std::vector< std::string > variable_names_
The names of the DOF that make up this group (this is just a sequence of joint variable names; not ne...
std::vector< std::string > default_states_names_
The names of the default states specified for this group in the SRDF.
const JointModel * common_root_
The joint that is a common root for all joints in this group (not necessarily part of this group)
void setEndEffectorName(const std::string &name)
Set the name of the end-effector, and remember this group is indeed an end-effector.
LinkModelMapConst link_model_map_
A map from link names to their instances.
std::vector< std::string > attached_end_effector_names_
If an end-effector is attached to this group, the name of that end-effector is stored in this variabl...
JointBoundsVector active_joint_models_bounds_
The bounds for all the active joint models.
JointModelGroup(const std::string &name, const srdf::Model::Group &config, const std::vector< const JointModel * > &joint_vector, const RobotModel *parent_model)
const std::pair< std::string, std::string > & getEndEffectorParentGroup() const
Get the name of the group this end-effector attaches to (first) and the name of the link in that grou...
JointModelMapConst joint_model_map_
A map from joint names to their instances. This includes all joints in the group.
const JointModel * getJointModel(const std::string &joint) const
Get a joint by its name. Throw an exception if the joint is not part of this group.
std::vector< const LinkModel * > updated_link_model_vector_
The list of downstream link models in the order they should be updated (may include links that are no...
std::set< std::string > variable_names_set_
The names of the DOF that make up this group (this is just a sequence of joint variable names; not ne...
bool enforcePositionBounds(double *state) const
const std::vector< std::string > & getAttachedEndEffectorNames() const
Get the names of the end effectors attached to this group.
const kinematics::KinematicsBaseConstPtr getSolverInstance() const
bool hasJointModel(const std::string &joint) const
Check if a joint is part of this group.
std::vector< int > active_joint_model_start_index_
For each active joint model in this group, hold the index at which the corresponding joint state star...
std::set< std::string > updated_link_model_with_geometry_name_set_
The list of downstream link names in the order they should be updated (may include links that are not...
const LinkModel * getLinkModel(const std::string &link) const
Get a link by its name. Throw an exception if the link is not part of this group.
void interpolate(const double *from, const double *to, double t, double *state) const
const moveit::core::LinkModel * getOnlyOneEndEffectorTip() const
Get one end effector tip, throwing an error if there ends up being more in the joint model group This...
std::vector< std::string > subgroup_names_
The set of labelled subgroups that are included in this group.
std::set< const LinkModel * > updated_link_model_set_
The list of downstream link models in the order they should be updated (may include links that are no...
bool isValidVelocityMove(const std::vector< double > &from_joint_pose, const std::vector< double > &to_joint_pose, double dt) const
Check that the time to move between two waypoints is sufficient given velocity limits.
unsigned int active_variable_count_
The number of variables necessary to describe the active joints in this group of joints.
bool hasLinkModel(const std::string &link) const
Check if a link is part of this group.
void updateMimicJoints(double *values) const
Update the variable values for the state of a group with respect to the mimic joints....
std::vector< GroupMimicUpdate > group_mimic_update_
bool satisfiesPositionBounds(const double *state, double margin=0.0) const
unsigned int variable_count_
The number of variables necessary to describe this group of joints.
const JointBoundsVector & getActiveJointModelsBounds() const
Get the bounds for all the active joints.
void addDefaultState(const std::string &name, const std::map< std::string, double > &default_state)
std::pair< KinematicsSolver, KinematicsSolverMap > group_kinematics_
void getSubgroups(std::vector< const JointModelGroup * > &sub_groups) const
Get the groups that are subsets of this one (in terms of joints set)
bool canSetStateFromIK(const std::string &tip) const
bool computeIKIndexBijection(const std::vector< std::string > &ik_jnames, std::vector< size_t > &joint_bijection) const
const std::vector< size_t > & getKinematicsSolverJointBijection() const
Return the mapping between the order of the joints in this group and the order of the joints in the k...
std::vector< const LinkModel * > link_model_with_geometry_vector_
std::set< std::string > updated_link_model_name_set_
The list of downstream link names in the order they should be updated (may include links that are not...
std::vector< const JointModel * > mimic_joints_
Joints that mimic other joints.
std::vector< std::string > link_model_name_vector_
The names of the links in this group.
VariableIndexMap joint_variables_index_map_
The group includes all the joint variables that make up the joints the group consists of....
bool getVariableDefaultPositions(const std::string &name, std::map< std::string, double > &values) const
Get the values that correspond to a named state as read from the URDF. Return false on failure.
std::vector< std::string > updated_link_model_with_geometry_name_vector_
The list of downstream link names in the order they should be updated (may include links that are not...
int getVariableGroupIndex(const std::string &variable) const
Get the index of a variable within the group. Return -1 on error.
std::pair< std::string, std::string > end_effector_parent_
First: name of the group that is parent to this end-effector group; Second: the link this in the pare...
std::vector< std::string > active_joint_model_name_vector_
Names of active joints in the order they appear in the group state.
const RobotModel * parent_model_
Owner model.
std::vector< std::string > joint_model_name_vector_
Names of joints in the order they appear in the group state.
void setSubgroupNames(const std::vector< std::string > &subgroups)
Set the names of the subgroups for this group.
void setEndEffectorParent(const std::string &group, const std::string &link)
If this group is an end-effector, specify the parent group (e.g., the arm holding the eef) and the li...
std::set< std::string > subgroup_names_set_
The set of labelled subgroups that are included in this group.
std::vector< std::string > link_model_with_geometry_name_vector_
The names of the links in this group that also have geometry.
std::vector< const JointModel * > fixed_joints_
The joints that have no DOF (fixed)
void printGroupInfo(std::ostream &out=std::cout) const
Print information about the constructed model.
std::string end_effector_name_
The name of the end effector, if this group is an end-effector.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
size_t getLocalVariableIndex(const std::string &variable) const
Get the index of the variable within this joint.
Definition: joint_model.cpp:85
size_t getFirstVariableIndex() const
Get the index of this joint's first variable within the full robot state.
Definition: joint_model.h:216
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
Definition: joint_model.h:210
const std::string & getName() const
Get the name of the joint.
Definition: joint_model.h:145
const std::vector< const LinkModel * > & getDescendantLinkModels() const
Get all the link models that descend from this joint, in the kinematic tree.
Definition: joint_model.h:404
const JointModel * getMimic() const
Get the joint this one is mimicking.
Definition: joint_model.h:372
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:72
const LinkTransformMap & getAssociatedFixedTransforms() const
Get the set of links that are attached to this one via fixed transforms. The returned transforms are ...
Definition: link_model.h:199
bool isContinuous() const
Check if this joint wraps around.
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.h:76
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a specific variable. Throw an exception of variable is not found.
Definition: robot_model.h:433
const JointModelGroup * getEndEffector(const std::string &name) const
Get the joint group that corresponds to a given end-effector name.
const JointModelGroup * getJointModelGroup(const std::string &name) const
Get a joint group from this model (by name)
const JointModel * getJointOfVariable(int variable_index) const
Definition: robot_model.h:213
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.
const JointModel * getCommonRoot(const JointModel *a, const JointModel *b) const
Get the deepest joint in the kinematic tree that is a common parent of both joints passed as argument...
Definition: robot_model.h:451
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
p
Definition: pick.py:62
a
Definition: plan.py:54
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:55
d
Definition: setup.py:4
name
Definition: setup.py:7
const rclcpp::Logger LOGGER
Definition: async_test.h:31
std::vector< size_t > bijection_
The mapping between the order of the joints in the group and the order of the joints in the kinematic...
SolverAllocatorFn allocator_
Function type that allocates a kinematics solver for a particular group.