moveit2
The MoveIt Motion Planning Framework for ROS 2.
robot_state.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, Sachin Chitta, Acorn Pooley, Mario Prats, Dave Coleman */
37 
38 #include <geometric_shapes/check_isometry.h>
39 #include <geometric_shapes/shape_operations.h>
43 #include <rclcpp/clock.hpp>
44 #include <rclcpp/logger.hpp>
45 #include <rclcpp/logging.hpp>
46 #include <rclcpp/time.hpp>
47 #include <tf2_eigen/tf2_eigen.hpp>
48 #include <cassert>
49 #include <functional>
52 
53 namespace moveit
54 {
55 namespace core
56 {
57 // Logger
58 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_robot_state.robot_state");
59 
60 RobotState::RobotState(const RobotModelConstPtr& robot_model)
61  : robot_model_(robot_model)
62  , has_velocity_(false)
63  , has_acceleration_(false)
64  , has_effort_(false)
65  , dirty_link_transforms_(nullptr)
66  , dirty_collision_body_transforms_(nullptr)
67  , rng_(nullptr)
68 {
69  if (robot_model == nullptr)
70  {
71  throw std::invalid_argument("RobotState cannot be constructed with nullptr RobotModelConstPtr");
72  }
73 
74  dirty_link_transforms_ = robot_model_->getRootJoint();
75  allocMemory();
76  initTransforms();
77 }
78 
79 RobotState::RobotState(const RobotState& other) : rng_(nullptr)
80 {
81  robot_model_ = other.robot_model_;
82  allocMemory();
83  copyFrom(other);
84 }
85 
87 {
89  free(memory_);
90  if (rng_)
91  delete rng_;
92 }
93 
94 void RobotState::allocMemory()
95 {
96  static_assert((sizeof(Eigen::Isometry3d) / EIGEN_MAX_ALIGN_BYTES) * EIGEN_MAX_ALIGN_BYTES == sizeof(Eigen::Isometry3d),
97  "sizeof(Eigen::Isometry3d) should be a multiple of EIGEN_MAX_ALIGN_BYTES");
98 
99  constexpr unsigned int extra_alignment_bytes = EIGEN_MAX_ALIGN_BYTES - 1;
100  // memory for the dirty joint transforms
101  const int nr_doubles_for_dirty_joint_transforms =
102  1 + robot_model_->getJointModelCount() / (sizeof(double) / sizeof(unsigned char));
103  const size_t bytes =
104  sizeof(Eigen::Isometry3d) * (robot_model_->getJointModelCount() + robot_model_->getLinkModelCount() +
105  robot_model_->getLinkGeometryCount()) +
106  sizeof(double) * (robot_model_->getVariableCount() * 3 + nr_doubles_for_dirty_joint_transforms) +
107  extra_alignment_bytes;
108  memory_ = malloc(bytes);
109 
110  // make the memory for transforms align at EIGEN_MAX_ALIGN_BYTES
111  // https://eigen.tuxfamily.org/dox/classEigen_1_1aligned__allocator.html
112  // NOLINTNEXTLINE(performance-no-int-to-ptr)
113  variable_joint_transforms_ = reinterpret_cast<Eigen::Isometry3d*>(((uintptr_t)memory_ + extra_alignment_bytes) &
114  ~(uintptr_t)extra_alignment_bytes);
115  global_link_transforms_ = variable_joint_transforms_ + robot_model_->getJointModelCount();
116  global_collision_body_transforms_ = global_link_transforms_ + robot_model_->getLinkModelCount();
117  dirty_joint_transforms_ =
118  reinterpret_cast<unsigned char*>(global_collision_body_transforms_ + robot_model_->getLinkGeometryCount());
119  position_ = reinterpret_cast<double*>(dirty_joint_transforms_) + nr_doubles_for_dirty_joint_transforms;
120  velocity_ = position_ + robot_model_->getVariableCount();
121  // acceleration and effort share the memory (not both can be specified)
122  effort_ = acceleration_ = velocity_ + robot_model_->getVariableCount();
123 }
124 
125 void RobotState::initTransforms()
126 {
127  // mark all transforms as dirty
128  const int nr_doubles_for_dirty_joint_transforms =
129  1 + robot_model_->getJointModelCount() / (sizeof(double) / sizeof(unsigned char));
130  memset(dirty_joint_transforms_, 1, sizeof(double) * nr_doubles_for_dirty_joint_transforms);
131 
132  // initialize last row of transformation matrices, which will not be modified by transform updates anymore
133  for (size_t i = 0, end = robot_model_->getJointModelCount() + robot_model_->getLinkModelCount() +
134  robot_model_->getLinkGeometryCount();
135  i != end; ++i)
136  variable_joint_transforms_[i].makeAffine();
137 }
138 
140 {
141  if (this != &other)
142  copyFrom(other);
143  return *this;
144 }
145 
146 void RobotState::copyFrom(const RobotState& other)
147 {
148  has_velocity_ = other.has_velocity_;
149  has_acceleration_ = other.has_acceleration_;
150  has_effort_ = other.has_effort_;
151 
152  dirty_collision_body_transforms_ = other.dirty_collision_body_transforms_;
153  dirty_link_transforms_ = other.dirty_link_transforms_;
154 
155  if (dirty_link_transforms_ == robot_model_->getRootJoint())
156  {
157  // everything is dirty; no point in copying transforms; copy positions, potentially velocity & acceleration
158  memcpy(position_, other.position_,
159  robot_model_->getVariableCount() * sizeof(double) *
160  (1 + (has_velocity_ ? 1 : 0) + ((has_acceleration_ || has_effort_) ? 1 : 0)));
161  // and just initialize transforms
162  initTransforms();
163  }
164  else
165  {
166  // copy all the memory; maybe avoid copying velocity and acceleration if possible
167  const int nr_doubles_for_dirty_joint_transforms =
168  1 + robot_model_->getJointModelCount() / (sizeof(double) / sizeof(unsigned char));
169  const size_t bytes =
170  sizeof(Eigen::Isometry3d) * (robot_model_->getJointModelCount() + robot_model_->getLinkModelCount() +
171  robot_model_->getLinkGeometryCount()) +
172  sizeof(double) *
173  (robot_model_->getVariableCount() * (1 + ((has_velocity_ || has_acceleration_ || has_effort_) ? 1 : 0) +
174  ((has_acceleration_ || has_effort_) ? 1 : 0)) +
175  nr_doubles_for_dirty_joint_transforms);
176  memcpy((void*)variable_joint_transforms_, (void*)other.variable_joint_transforms_, bytes);
177  }
178 
179  // copy attached bodies
181  for (const auto& attached_body : other.attached_body_map_)
182  attachBody(std::make_unique<AttachedBody>(*attached_body.second));
183 }
184 
185 bool RobotState::checkJointTransforms(const JointModel* joint) const
186 {
187  if (dirtyJointTransform(joint))
188  {
189  RCLCPP_WARN(LOGGER, "Returning dirty joint transforms for joint '%s'", joint->getName().c_str());
190  return false;
191  }
192  return true;
193 }
194 
195 bool RobotState::checkLinkTransforms() const
196 {
197  if (dirtyLinkTransforms())
198  {
199  RCLCPP_WARN(LOGGER, "Returning dirty link transforms");
200  return false;
201  }
202  return true;
203 }
204 
205 bool RobotState::checkCollisionTransforms() const
206 {
208  {
209  RCLCPP_WARN(LOGGER, "Returning dirty collision body transforms");
210  return false;
211  }
212  return true;
213 }
214 
215 void RobotState::markVelocity()
216 {
217  if (!has_velocity_)
218  {
219  has_velocity_ = true;
220  memset(velocity_, 0, sizeof(double) * robot_model_->getVariableCount());
221  }
222 }
223 
224 void RobotState::markAcceleration()
225 {
226  if (!has_acceleration_)
227  {
228  has_acceleration_ = true;
229  has_effort_ = false;
230  memset(acceleration_, 0, sizeof(double) * robot_model_->getVariableCount());
231  }
232 }
233 
234 void RobotState::markEffort()
235 {
236  if (!has_effort_)
237  {
238  has_acceleration_ = false;
239  has_effort_ = true;
240  memset(effort_, 0, sizeof(double) * robot_model_->getVariableCount());
241  }
242 }
243 
245 {
246  has_velocity_ = false;
247  markVelocity();
248 }
249 
251 {
252  has_acceleration_ = false;
253  markAcceleration();
254 }
255 
257 {
258  has_effort_ = false;
259  markEffort();
260 }
261 
263 {
264  has_velocity_ = false;
265 }
266 
268 {
269  has_acceleration_ = false;
270 }
271 
273 {
274  has_effort_ = false;
275 }
276 
278 {
279  dropVelocities();
281  dropEffort();
282 }
283 
285 {
286  random_numbers::RandomNumberGenerator& rng = getRandomNumberGenerator();
287  robot_model_->getVariableRandomPositions(rng, position_);
288  memset(dirty_joint_transforms_, 1, robot_model_->getJointModelCount() * sizeof(unsigned char));
289  dirty_link_transforms_ = robot_model_->getRootJoint();
290  // mimic values are correctly set in RobotModel
291 }
292 
294 {
295  // we do not make calls to RobotModel for random number generation because mimic joints
296  // could trigger updates outside the state of the group itself
297  random_numbers::RandomNumberGenerator& rng = getRandomNumberGenerator();
299 }
300 void RobotState::setToRandomPositions(const JointModelGroup* group, random_numbers::RandomNumberGenerator& rng)
301 {
302  const std::vector<const JointModel*>& joints = group->getActiveJointModels();
303  for (const JointModel* joint : joints)
304  joint->getVariableRandomPositions(rng, position_ + joint->getFirstVariableIndex());
305  updateMimicJoints(group);
306 }
307 
309  const std::vector<double>& distances)
310 {
311  // we do not make calls to RobotModel for random number generation because mimic joints
312  // could trigger updates outside the state of the group itself
313  random_numbers::RandomNumberGenerator& rng = getRandomNumberGenerator();
314  setToRandomPositionsNearBy(group, seed, distances, rng);
315 }
316 
318  const std::vector<double>& distances,
319  random_numbers::RandomNumberGenerator& rng)
320 {
321  const std::vector<const JointModel*>& joints = group->getActiveJointModels();
322  assert(distances.size() == joints.size());
323  for (std::size_t i = 0; i < joints.size(); ++i)
324  {
325  const int idx = joints[i]->getFirstVariableIndex();
326  joints[i]->getVariableRandomPositionsNearBy(rng, position_ + joints[i]->getFirstVariableIndex(),
327  seed.position_ + idx, distances[i]);
328  }
329  updateMimicJoints(group);
330 }
331 
333 {
334  // we do not make calls to RobotModel for random number generation because mimic joints
335  // could trigger updates outside the state of the group itself
336  random_numbers::RandomNumberGenerator& rng = getRandomNumberGenerator();
338 }
339 
341  random_numbers::RandomNumberGenerator& rng)
342 {
343  const std::vector<const JointModel*>& joints = group->getActiveJointModels();
344  for (const JointModel* joint : joints)
345  {
346  const int idx = joint->getFirstVariableIndex();
347  joint->getVariableRandomPositionsNearBy(rng, position_ + joint->getFirstVariableIndex(), seed.position_ + idx,
348  distance);
349  }
350  updateMimicJoints(group);
351 }
352 
354 {
355  std::map<std::string, double> m;
356  bool r = group->getVariableDefaultPositions(name, m); // mimic values are updated
358  return r;
359 }
360 
362 {
363  robot_model_->getVariableDefaultPositions(position_); // mimic values are updated
364  // set velocity & acceleration to 0
365  memset(velocity_, 0, sizeof(double) * 2 * robot_model_->getVariableCount());
366  memset(dirty_joint_transforms_, 1, robot_model_->getJointModelCount() * sizeof(unsigned char));
367  dirty_link_transforms_ = robot_model_->getRootJoint();
368 }
369 
370 void RobotState::setVariablePositions(const double* position)
371 {
372  // assume everything is in order in terms of array lengths (for efficiency reasons)
373  memcpy(position_, position, robot_model_->getVariableCount() * sizeof(double));
374 
375  // the full state includes mimic joint values, so no need to update mimic here
376 
377  // Since all joint values have potentially changed, we will need to recompute all transforms
378  memset(dirty_joint_transforms_, 1, robot_model_->getJointModelCount() * sizeof(unsigned char));
379  dirty_link_transforms_ = robot_model_->getRootJoint();
380 }
381 
382 void RobotState::setVariablePositions(const std::map<std::string, double>& variable_map)
383 {
384  for (const std::pair<const std::string, double>& it : variable_map)
385  {
386  const int index = robot_model_->getVariableIndex(it.first);
387  position_[index] = it.second;
388  const JointModel* jm = robot_model_->getJointOfVariable(index);
389  markDirtyJointTransforms(jm);
390  updateMimicJoint(jm);
391  }
392 }
393 
394 void RobotState::getMissingKeys(const std::map<std::string, double>& variable_map,
395  std::vector<std::string>& missing_variables) const
396 {
397  missing_variables.clear();
398  const std::vector<std::string>& nm = robot_model_->getVariableNames();
399  for (const std::string& variable_name : nm)
400  if (variable_map.find(variable_name) == variable_map.end())
401  if (robot_model_->getJointOfVariable(variable_name)->getMimic() == nullptr)
402  missing_variables.push_back(variable_name);
403 }
404 
405 void RobotState::setVariablePositions(const std::map<std::string, double>& variable_map,
406  std::vector<std::string>& missing_variables)
407 {
408  setVariablePositions(variable_map);
409  getMissingKeys(variable_map, missing_variables);
410 }
411 
412 void RobotState::setVariablePositions(const std::vector<std::string>& variable_names,
413  const std::vector<double>& variable_position)
414 {
415  for (std::size_t i = 0; i < variable_names.size(); ++i)
416  {
417  const int index = robot_model_->getVariableIndex(variable_names[i]);
418  position_[index] = variable_position[i];
419  const JointModel* jm = robot_model_->getJointOfVariable(index);
420  markDirtyJointTransforms(jm);
421  updateMimicJoint(jm);
422  }
423 }
424 
425 void RobotState::setVariableVelocities(const std::map<std::string, double>& variable_map)
426 {
427  markVelocity();
428  for (const std::pair<const std::string, double>& it : variable_map)
429  velocity_[robot_model_->getVariableIndex(it.first)] = it.second;
430 }
431 
432 void RobotState::setVariableVelocities(const std::map<std::string, double>& variable_map,
433  std::vector<std::string>& missing_variables)
434 {
435  setVariableVelocities(variable_map);
436  getMissingKeys(variable_map, missing_variables);
437 }
438 
439 void RobotState::setVariableVelocities(const std::vector<std::string>& variable_names,
440  const std::vector<double>& variable_velocity)
441 {
442  markVelocity();
443  assert(variable_names.size() == variable_velocity.size());
444  for (std::size_t i = 0; i < variable_names.size(); ++i)
445  velocity_[robot_model_->getVariableIndex(variable_names[i])] = variable_velocity[i];
446 }
447 
448 void RobotState::setVariableAccelerations(const std::map<std::string, double>& variable_map)
449 {
450  markAcceleration();
451  for (const std::pair<const std::string, double>& it : variable_map)
452  acceleration_[robot_model_->getVariableIndex(it.first)] = it.second;
453 }
454 
455 void RobotState::setVariableAccelerations(const std::map<std::string, double>& variable_map,
456  std::vector<std::string>& missing_variables)
457 {
458  setVariableAccelerations(variable_map);
459  getMissingKeys(variable_map, missing_variables);
460 }
461 
462 void RobotState::setVariableAccelerations(const std::vector<std::string>& variable_names,
463  const std::vector<double>& variable_acceleration)
464 {
465  markAcceleration();
466  assert(variable_names.size() == variable_acceleration.size());
467  for (std::size_t i = 0; i < variable_names.size(); ++i)
468  acceleration_[robot_model_->getVariableIndex(variable_names[i])] = variable_acceleration[i];
469 }
470 
471 void RobotState::setVariableEffort(const std::map<std::string, double>& variable_map)
472 {
473  markEffort();
474  for (const std::pair<const std::string, double>& it : variable_map)
475  effort_[robot_model_->getVariableIndex(it.first)] = it.second;
476 }
477 
478 void RobotState::setVariableEffort(const std::map<std::string, double>& variable_map,
479  std::vector<std::string>& missing_variables)
480 {
481  setVariableEffort(variable_map);
482  getMissingKeys(variable_map, missing_variables);
483 }
484 
485 void RobotState::setVariableEffort(const std::vector<std::string>& variable_names,
486  const std::vector<double>& variable_effort)
487 {
488  markEffort();
489  assert(variable_names.size() == variable_effort.size());
490  for (std::size_t i = 0; i < variable_names.size(); ++i)
491  effort_[robot_model_->getVariableIndex(variable_names[i])] = variable_effort[i];
492 }
493 
495 {
496  if (has_velocity_)
497  {
498  for (size_t i = 0; i < robot_model_->getVariableCount(); ++i)
499  velocity_[i] *= -1;
500  }
501 }
502 
503 void RobotState::setJointEfforts(const JointModel* joint, const double* effort)
504 {
505  if (has_acceleration_)
506  {
507  RCLCPP_ERROR(LOGGER, "Unable to set joint efforts because array is being used for accelerations");
508  return;
509  }
510  has_effort_ = true;
511 
512  memcpy(effort_ + joint->getFirstVariableIndex(), effort, joint->getVariableCount() * sizeof(double));
513 }
514 
515 void RobotState::setJointGroupPositions(const JointModelGroup* group, const double* gstate)
516 {
517  const std::vector<int>& il = group->getVariableIndexList();
518  if (group->isContiguousWithinState())
519  memcpy(position_ + il[0], gstate, group->getVariableCount() * sizeof(double));
520  else
521  {
522  for (std::size_t i = 0; i < il.size(); ++i)
523  position_[il[i]] = gstate[i];
524  }
525  updateMimicJoints(group);
526 }
527 
528 void RobotState::setJointGroupPositions(const JointModelGroup* group, const Eigen::VectorXd& values)
529 {
530  const std::vector<int>& il = group->getVariableIndexList();
531  for (std::size_t i = 0; i < il.size(); ++i)
532  position_[il[i]] = values(i);
533  updateMimicJoints(group);
534 }
535 
536 void RobotState::setJointGroupActivePositions(const JointModelGroup* group, const std::vector<double>& gstate)
537 {
538  assert(gstate.size() == group->getActiveVariableCount());
539  std::size_t i = 0;
540  for (const JointModel* jm : group->getActiveJointModels())
541  {
542  setJointPositions(jm, &gstate[i]);
543  i += jm->getVariableCount();
544  }
545  updateMimicJoints(group);
546 }
547 
548 void RobotState::setJointGroupActivePositions(const JointModelGroup* group, const Eigen::VectorXd& values)
549 {
550  assert(values.size() == group->getActiveVariableCount());
551  std::size_t i = 0;
552  for (const JointModel* jm : group->getActiveJointModels())
553  {
554  setJointPositions(jm, &values(i));
555  i += jm->getVariableCount();
556  }
557  updateMimicJoints(group);
558 }
559 
561 {
562  const std::vector<int>& il = group->getVariableIndexList();
563  if (group->isContiguousWithinState())
564  memcpy(gstate, position_ + il[0], group->getVariableCount() * sizeof(double));
565  else
566  for (std::size_t i = 0; i < il.size(); ++i)
567  gstate[i] = position_[il[i]];
568 }
569 
570 void RobotState::copyJointGroupPositions(const JointModelGroup* group, Eigen::VectorXd& values) const
571 {
572  const std::vector<int>& il = group->getVariableIndexList();
573  values.resize(il.size());
574  for (std::size_t i = 0; i < il.size(); ++i)
575  values(i) = position_[il[i]];
576 }
577 
579 {
580  markVelocity();
581  const std::vector<int>& il = group->getVariableIndexList();
582  if (group->isContiguousWithinState())
583  memcpy(velocity_ + il[0], gstate, group->getVariableCount() * sizeof(double));
584  else
585  {
586  for (std::size_t i = 0; i < il.size(); ++i)
587  velocity_[il[i]] = gstate[i];
588  }
589 }
590 
591 void RobotState::setJointGroupVelocities(const JointModelGroup* group, const Eigen::VectorXd& values)
592 {
593  markVelocity();
594  const std::vector<int>& il = group->getVariableIndexList();
595  for (std::size_t i = 0; i < il.size(); ++i)
596  velocity_[il[i]] = values(i);
597 }
598 
600 {
601  const std::vector<int>& il = group->getVariableIndexList();
602  if (group->isContiguousWithinState())
603  memcpy(gstate, velocity_ + il[0], group->getVariableCount() * sizeof(double));
604  else
605  for (std::size_t i = 0; i < il.size(); ++i)
606  gstate[i] = velocity_[il[i]];
607 }
608 
609 void RobotState::copyJointGroupVelocities(const JointModelGroup* group, Eigen::VectorXd& values) const
610 {
611  const std::vector<int>& il = group->getVariableIndexList();
612  values.resize(il.size());
613  for (std::size_t i = 0; i < il.size(); ++i)
614  values(i) = velocity_[il[i]];
615 }
616 
618 {
619  markAcceleration();
620  const std::vector<int>& il = group->getVariableIndexList();
621  if (group->isContiguousWithinState())
622  memcpy(acceleration_ + il[0], gstate, group->getVariableCount() * sizeof(double));
623  else
624  {
625  for (std::size_t i = 0; i < il.size(); ++i)
626  acceleration_[il[i]] = gstate[i];
627  }
628 }
629 
630 void RobotState::setJointGroupAccelerations(const JointModelGroup* group, const Eigen::VectorXd& values)
631 {
632  markAcceleration();
633  const std::vector<int>& il = group->getVariableIndexList();
634  for (std::size_t i = 0; i < il.size(); ++i)
635  acceleration_[il[i]] = values(i);
636 }
637 
639 {
640  const std::vector<int>& il = group->getVariableIndexList();
641  if (group->isContiguousWithinState())
642  memcpy(gstate, acceleration_ + il[0], group->getVariableCount() * sizeof(double));
643  else
644  for (std::size_t i = 0; i < il.size(); ++i)
645  gstate[i] = acceleration_[il[i]];
646 }
647 
648 void RobotState::copyJointGroupAccelerations(const JointModelGroup* group, Eigen::VectorXd& values) const
649 {
650  const std::vector<int>& il = group->getVariableIndexList();
651  values.resize(il.size());
652  for (std::size_t i = 0; i < il.size(); ++i)
653  values(i) = acceleration_[il[i]];
654 }
655 
656 void RobotState::update(bool force)
657 {
658  // make sure we do everything from scratch if needed
659  if (force)
660  {
661  memset(dirty_joint_transforms_, 1, robot_model_->getJointModelCount() * sizeof(unsigned char));
662  dirty_link_transforms_ = robot_model_->getRootJoint();
663  }
664 
665  // this actually triggers all needed updates
667 }
668 
670 {
671  if (dirty_link_transforms_ != nullptr)
673 
674  if (dirty_collision_body_transforms_ != nullptr)
675  {
676  const std::vector<const LinkModel*>& links = dirty_collision_body_transforms_->getDescendantLinkModels();
677  dirty_collision_body_transforms_ = nullptr;
678 
679  for (const LinkModel* link : links)
680  {
681  const EigenSTL::vector_Isometry3d& ot = link->getCollisionOriginTransforms();
682  const std::vector<int>& ot_id = link->areCollisionOriginTransformsIdentity();
683  const int index_co = link->getFirstCollisionBodyTransformIndex();
684  const int index_l = link->getLinkIndex();
685  for (std::size_t j = 0, end = ot.size(); j != end; ++j)
686  {
687  if (ot_id[j])
688  global_collision_body_transforms_[index_co + j] = global_link_transforms_[index_l];
689  else
690  global_collision_body_transforms_[index_co + j].affine().noalias() =
691  global_link_transforms_[index_l].affine() * ot[j].matrix();
692  }
693  }
694  }
695 }
696 
698 {
699  if (dirty_link_transforms_ != nullptr)
700  {
701  updateLinkTransformsInternal(dirty_link_transforms_);
702  if (dirty_collision_body_transforms_)
703  dirty_collision_body_transforms_ =
704  robot_model_->getCommonRoot(dirty_collision_body_transforms_, dirty_link_transforms_);
705  else
706  dirty_collision_body_transforms_ = dirty_link_transforms_;
707  dirty_link_transforms_ = nullptr;
708  }
709 }
710 
711 void RobotState::updateLinkTransformsInternal(const JointModel* start)
712 {
713  for (const LinkModel* link : start->getDescendantLinkModels())
714  {
715  int idx_link = link->getLinkIndex();
716  const LinkModel* parent = link->getParentLinkModel();
717  if (parent) // root JointModel will not have a parent
718  {
719  int idx_parent = parent->getLinkIndex();
720  if (link->parentJointIsFixed()) // fixed joint
721  global_link_transforms_[idx_link].affine().noalias() =
722  global_link_transforms_[idx_parent].affine() * link->getJointOriginTransform().matrix();
723  else // non-fixed joint
724  {
725  if (link->jointOriginTransformIsIdentity()) // Link has identity transform
726  global_link_transforms_[idx_link].affine().noalias() =
727  global_link_transforms_[idx_parent].affine() * getJointTransform(link->getParentJointModel()).matrix();
728  else // Link has non-identity transform
729  global_link_transforms_[idx_link].affine().noalias() =
730  global_link_transforms_[idx_parent].affine() * link->getJointOriginTransform().matrix() *
731  getJointTransform(link->getParentJointModel()).matrix();
732  }
733  }
734  else // is the origin / root / 'model frame'
735  {
736  if (link->jointOriginTransformIsIdentity())
737  global_link_transforms_[idx_link] = getJointTransform(link->getParentJointModel());
738  else
739  global_link_transforms_[idx_link].affine().noalias() =
740  link->getJointOriginTransform().affine() * getJointTransform(link->getParentJointModel()).matrix();
741  }
742  }
743 
744  // update attached bodies tf; these are usually very few, so we update them all
745  for (const auto& attached_body : attached_body_map_)
746  attached_body.second->computeTransform(
747  global_link_transforms_[attached_body.second->getAttachedLink()->getLinkIndex()]);
748 }
749 
750 void RobotState::updateStateWithLinkAt(const LinkModel* link, const Eigen::Isometry3d& transform, bool backward)
751 {
752  updateLinkTransforms(); // no link transforms must be dirty, otherwise the transform we set will be overwritten
753 
754  // update the fact that collision body transforms are out of date
755  if (dirty_collision_body_transforms_)
756  dirty_collision_body_transforms_ =
757  robot_model_->getCommonRoot(dirty_collision_body_transforms_, link->getParentJointModel());
758  else
759  dirty_collision_body_transforms_ = link->getParentJointModel();
760 
761  global_link_transforms_[link->getLinkIndex()] = transform;
762 
763  // update link transforms for descendant links only (leaving the transform for the current link untouched)
764  const std::vector<const JointModel*>& cj = link->getChildJointModels();
765  for (const JointModel* joint : cj)
766  updateLinkTransformsInternal(joint);
767 
768  // if we also need to go backward
769  if (backward)
770  {
771  const LinkModel* parent_link = link;
772  const LinkModel* child_link;
773  while (parent_link->getParentJointModel()->getParentLinkModel())
774  {
775  child_link = parent_link;
776  parent_link = parent_link->getParentJointModel()->getParentLinkModel();
777 
778  // update the transform of the parent
779  global_link_transforms_[parent_link->getLinkIndex()] =
780  global_link_transforms_[child_link->getLinkIndex()] *
781  (child_link->getJointOriginTransform() *
782  variable_joint_transforms_[child_link->getParentJointModel()->getJointIndex()])
783  .inverse();
784 
785  // update link transforms for descendant links only (leaving the transform for the current link untouched)
786  // with the exception of the child link we are coming backwards from
787  const std::vector<const JointModel*>& cj = parent_link->getChildJointModels();
788  for (const JointModel* joint : cj)
789  if (joint != child_link->getParentJointModel())
790  updateLinkTransformsInternal(joint);
791  }
792  // all collision body transforms are invalid now
793  dirty_collision_body_transforms_ = parent_link->getParentJointModel();
794  }
795 
796  // update attached bodies tf; these are usually very few, so we update them all
797  for (const auto& attached_body : attached_body_map_)
798  attached_body.second->computeTransform(
799  global_link_transforms_[attached_body.second->getAttachedLink()->getLinkIndex()]);
800 }
801 
802 const LinkModel* RobotState::getRigidlyConnectedParentLinkModel(const std::string& frame) const
803 {
804  bool found;
805  const LinkModel* link{ nullptr };
806  getFrameInfo(frame, link, found);
807  if (!found)
808  RCLCPP_ERROR(LOGGER, "Unable to find link for frame '%s'", frame.c_str());
809  return getRobotModel()->getRigidlyConnectedParentLinkModel(link);
810 }
811 
812 bool RobotState::satisfiesBounds(double margin) const
813 {
814  const std::vector<const JointModel*>& jm = robot_model_->getActiveJointModels();
815  for (const JointModel* joint : jm)
816  if (!satisfiesBounds(joint, margin))
817  return false;
818  return true;
819 }
820 
821 bool RobotState::satisfiesBounds(const JointModelGroup* group, double margin) const
822 {
823  const std::vector<const JointModel*>& jm = group->getActiveJointModels();
824  for (const JointModel* joint : jm)
825  if (!satisfiesBounds(joint, margin))
826  return false;
827  return true;
828 }
829 
831 {
832  const std::vector<const JointModel*>& jm = robot_model_->getActiveJointModels();
833  for (const JointModel* joint : jm)
834  enforceBounds(joint);
835 }
836 
838 {
839  const std::vector<const JointModel*>& jm = joint_group->getActiveJointModels();
840  for (const JointModel* joint : jm)
841  enforceBounds(joint);
842 }
843 
845 {
846  for (const JointModel* jm : robot_model_->getActiveJointModels())
847  harmonizePosition(jm);
848 }
849 
851 {
852  for (const JointModel* jm : joint_group->getActiveJointModels())
853  harmonizePosition(jm);
854 }
855 
856 std::pair<double, const JointModel*> RobotState::getMinDistanceToPositionBounds() const
857 {
858  return getMinDistanceToPositionBounds(robot_model_->getActiveJointModels());
859 }
860 
861 std::pair<double, const JointModel*> RobotState::getMinDistanceToPositionBounds(const JointModelGroup* group) const
862 {
863  return getMinDistanceToPositionBounds(group->getActiveJointModels());
864 }
865 
866 std::pair<double, const JointModel*>
867 RobotState::getMinDistanceToPositionBounds(const std::vector<const JointModel*>& joints) const
868 {
869  double distance = std::numeric_limits<double>::max();
870  const JointModel* index = nullptr;
871  for (const JointModel* joint : joints)
872  {
873  if (joint->getType() == JointModel::PLANAR || joint->getType() == JointModel::FLOATING)
874  continue;
875  if (joint->getType() == JointModel::REVOLUTE)
876  if (static_cast<const RevoluteJointModel*>(joint)->isContinuous())
877  continue;
878 
879  const double* joint_values = getJointPositions(joint);
880  const JointModel::Bounds& bounds = joint->getVariableBounds();
881  std::vector<double> lower_bounds(bounds.size()), upper_bounds(bounds.size());
882  for (std::size_t j = 0; j < bounds.size(); ++j)
883  {
884  lower_bounds[j] = bounds[j].min_position_;
885  upper_bounds[j] = bounds[j].max_position_;
886  }
887  double new_distance = joint->distance(joint_values, &lower_bounds[0]);
888  if (new_distance < distance)
889  {
890  index = joint;
891  distance = new_distance;
892  }
893  new_distance = joint->distance(joint_values, &upper_bounds[0]);
894  if (new_distance < distance)
895  {
896  index = joint;
897  distance = new_distance;
898  }
899  }
900  return std::make_pair(distance, index);
901 }
902 
903 bool RobotState::isValidVelocityMove(const RobotState& other, const JointModelGroup* group, double dt) const
904 {
905  const std::vector<const JointModel*>& jm = group->getActiveJointModels();
906  for (const JointModel* joint_id : jm)
907  {
908  const int idx = joint_id->getFirstVariableIndex();
909  const std::vector<VariableBounds>& bounds = joint_id->getVariableBounds();
910 
911  // Check velocity for each joint variable
912  for (std::size_t var_id = 0; var_id < joint_id->getVariableCount(); ++var_id)
913  {
914  const double dtheta = std::abs(*(position_ + idx + var_id) - *(other.getVariablePositions() + idx + var_id));
915 
916  if (dtheta > dt * bounds[var_id].max_velocity_)
917  return false;
918  }
919  }
920  return true;
921 }
922 
923 double RobotState::distance(const RobotState& other, const JointModelGroup* joint_group) const
924 {
925  double d = 0.0;
926  const std::vector<const JointModel*>& jm = joint_group->getActiveJointModels();
927  for (const JointModel* joint : jm)
928  {
929  const int idx = joint->getFirstVariableIndex();
930  d += joint->getDistanceFactor() * joint->distance(position_ + idx, other.position_ + idx);
931  }
932  return d;
933 }
934 
935 void RobotState::interpolate(const RobotState& to, double t, RobotState& state) const
936 {
937  moveit::core::checkInterpolationParamBounds(LOGGER, t);
938  robot_model_->interpolate(getVariablePositions(), to.getVariablePositions(), t, state.getVariablePositions());
939 
940  memset(state.dirty_joint_transforms_, 1, state.robot_model_->getJointModelCount() * sizeof(unsigned char));
941  state.dirty_link_transforms_ = state.robot_model_->getRootJoint();
942 }
943 
944 void RobotState::interpolate(const RobotState& to, double t, RobotState& state, const JointModelGroup* joint_group) const
945 {
946  moveit::core::checkInterpolationParamBounds(LOGGER, t);
947  const std::vector<const JointModel*>& jm = joint_group->getActiveJointModels();
948  for (const JointModel* joint : jm)
949  {
950  const int idx = joint->getFirstVariableIndex();
951  joint->interpolate(position_ + idx, to.position_ + idx, t, state.position_ + idx);
952  }
953  state.updateMimicJoints(joint_group);
954 }
955 
957 {
958  attached_body_update_callback_ = callback;
959 }
960 
961 bool RobotState::hasAttachedBody(const std::string& id) const
962 {
963  return attached_body_map_.find(id) != attached_body_map_.end();
964 }
965 
966 const AttachedBody* RobotState::getAttachedBody(const std::string& id) const
967 {
968  const auto it = attached_body_map_.find(id);
969  if (it == attached_body_map_.end())
970  {
971  RCLCPP_ERROR(LOGGER, "Attached body '%s' not found", id.c_str());
972  return nullptr;
973  }
974  else
975  return it->second.get();
976 }
977 
978 void RobotState::attachBody(std::unique_ptr<AttachedBody> attached_body)
979 {
980  // If an attached body with the same id exists, remove it
981  clearAttachedBody(attached_body->getName());
982 
983  attached_body->computeTransform(getGlobalLinkTransform(attached_body->getAttachedLink()));
984  if (attached_body_update_callback_)
985  attached_body_update_callback_(attached_body.get(), true);
986  attached_body_map_[attached_body->getName()] = std::move(attached_body);
987 }
988 
990 {
991  attachBody(std::unique_ptr<AttachedBody>(attached_body));
992 }
993 
994 void RobotState::attachBody(const std::string& id, const Eigen::Isometry3d& pose,
995  const std::vector<shapes::ShapeConstPtr>& shapes,
996  const EigenSTL::vector_Isometry3d& shape_poses, const std::set<std::string>& touch_links,
997  const std::string& link, const trajectory_msgs::msg::JointTrajectory& detach_posture,
998  const moveit::core::FixedTransformsMap& subframe_poses)
999 {
1000  attachBody(std::make_unique<AttachedBody>(robot_model_->getLinkModel(link), id, pose, shapes, shape_poses,
1001  touch_links, detach_posture, subframe_poses));
1002 }
1003 
1004 void RobotState::getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies) const
1005 {
1006  attached_bodies.clear();
1007  attached_bodies.reserve(attached_body_map_.size());
1008  for (const auto& it : attached_body_map_)
1009  attached_bodies.push_back(it.second.get());
1010 }
1011 
1012 void RobotState::getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies, const JointModelGroup* group) const
1013 {
1014  attached_bodies.clear();
1015  for (const auto& it : attached_body_map_)
1016  if (group->hasLinkModel(it.second->getAttachedLinkName()))
1017  attached_bodies.push_back(it.second.get());
1018 }
1019 
1020 void RobotState::getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies, const LinkModel* link_model) const
1021 {
1022  attached_bodies.clear();
1023  for (const auto& it : attached_body_map_)
1024  if (it.second->getAttachedLink() == link_model)
1025  attached_bodies.push_back(it.second.get());
1026 }
1027 
1029 {
1030  for (const auto& it : attached_body_map_)
1031  {
1032  if (attached_body_update_callback_)
1033  attached_body_update_callback_(it.second.get(), false);
1034  }
1035  attached_body_map_.clear();
1036 }
1037 
1039 {
1040  for (auto it = attached_body_map_.cbegin(); it != attached_body_map_.cend(); ++it)
1041  {
1042  if (it->second->getAttachedLink() != link)
1043  {
1044  continue;
1045  }
1046  if (attached_body_update_callback_)
1047  attached_body_update_callback_(it->second.get(), false);
1048  const auto del = it++;
1049  attached_body_map_.erase(del);
1050  }
1051 }
1052 
1054 {
1055  for (auto it = attached_body_map_.cbegin(); it != attached_body_map_.cend(); ++it)
1056  {
1057  if (!group->hasLinkModel(it->second->getAttachedLinkName()))
1058  {
1059  continue;
1060  }
1061  if (attached_body_update_callback_)
1062  attached_body_update_callback_(it->second.get(), false);
1063  const auto del = it++;
1064  attached_body_map_.erase(del);
1065  }
1066 }
1067 
1068 bool RobotState::clearAttachedBody(const std::string& id)
1069 {
1070  const auto it = attached_body_map_.find(id);
1071  if (it != attached_body_map_.end())
1072  {
1073  if (attached_body_update_callback_)
1074  attached_body_update_callback_(it->second.get(), false);
1075  attached_body_map_.erase(it);
1076  return true;
1077  }
1078  else
1079  return false;
1080 }
1081 
1082 const Eigen::Isometry3d& RobotState::getFrameTransform(const std::string& frame_id, bool* frame_found)
1083 {
1085  return static_cast<const RobotState*>(this)->getFrameTransform(frame_id, frame_found);
1086 }
1087 
1088 const Eigen::Isometry3d& RobotState::getFrameTransform(const std::string& frame_id, bool* frame_found) const
1089 {
1090  const LinkModel* ignored_link;
1091  bool found;
1092  const auto& result = getFrameInfo(frame_id, ignored_link, found);
1093 
1094  if (frame_found)
1095  *frame_found = found;
1096  else if (!found)
1097  RCLCPP_WARN(LOGGER, "getFrameTransform() did not find a frame with name %s.", frame_id.c_str());
1098 
1099  return result;
1100 }
1101 
1102 const Eigen::Isometry3d& RobotState::getFrameInfo(const std::string& frame_id, const LinkModel*& robot_link,
1103  bool& frame_found) const
1104 {
1105  if (!frame_id.empty() && frame_id[0] == '/')
1106  return getFrameInfo(frame_id.substr(1), robot_link, frame_found);
1107 
1108  static const Eigen::Isometry3d IDENTITY_TRANSFORM = Eigen::Isometry3d::Identity();
1109  if (frame_id == robot_model_->getModelFrame())
1110  {
1111  robot_link = robot_model_->getRootLink();
1112  frame_found = true;
1113  return IDENTITY_TRANSFORM;
1114  }
1115  if ((robot_link = robot_model_->getLinkModel(frame_id, &frame_found)))
1116  {
1117  assert(checkLinkTransforms());
1118  return global_link_transforms_[robot_link->getLinkIndex()];
1119  }
1120  robot_link = nullptr;
1121 
1122  // Check names of the attached bodies
1123  const auto jt = attached_body_map_.find(frame_id);
1124  if (jt != attached_body_map_.end())
1125  {
1126  const Eigen::Isometry3d& transform = jt->second->getGlobalPose();
1127  robot_link = jt->second->getAttachedLink();
1128  frame_found = true;
1129  assert(checkLinkTransforms());
1130  return transform;
1131  }
1132 
1133  // Check if an AttachedBody has a subframe with name frame_id
1134  for (const auto& body : attached_body_map_)
1135  {
1136  const Eigen::Isometry3d& transform = body.second->getGlobalSubframeTransform(frame_id, &frame_found);
1137  if (frame_found)
1138  {
1139  robot_link = body.second->getAttachedLink();
1140  assert(checkLinkTransforms());
1141  return transform;
1142  }
1143  }
1144 
1145  robot_link = nullptr;
1146  frame_found = false;
1147  return IDENTITY_TRANSFORM;
1148 }
1149 
1150 bool RobotState::knowsFrameTransform(const std::string& frame_id) const
1151 {
1152  if (!frame_id.empty() && frame_id[0] == '/')
1153  return knowsFrameTransform(frame_id.substr(1));
1154  if (robot_model_->hasLinkModel(frame_id))
1155  return true;
1156 
1157  // Check if an AttachedBody with name frame_id exists
1158  const auto it = attached_body_map_.find(frame_id);
1159  if (it != attached_body_map_.end())
1160  return !it->second->getGlobalCollisionBodyTransforms().empty();
1161 
1162  // Check if an AttachedBody has a subframe with name frame_id
1163  for (const auto& body : attached_body_map_)
1164  {
1165  if (body.second->hasSubframeTransform(frame_id))
1166  return true;
1167  }
1168  return false;
1169 }
1170 
1171 void RobotState::getRobotMarkers(visualization_msgs::msg::MarkerArray& arr, const std::vector<std::string>& link_names,
1172  const std_msgs::msg::ColorRGBA& color, const std::string& ns,
1173  const rclcpp::Duration& dur, bool include_attached) const
1174 {
1175  std::size_t cur_num = arr.markers.size();
1176  getRobotMarkers(arr, link_names, include_attached);
1177  unsigned int id = cur_num;
1178  for (std::size_t i = cur_num; i < arr.markers.size(); ++i, ++id)
1179  {
1180  arr.markers[i].ns = ns;
1181  arr.markers[i].id = id;
1182  arr.markers[i].lifetime = dur;
1183  arr.markers[i].color = color;
1184  }
1185 }
1186 
1187 void RobotState::getRobotMarkers(visualization_msgs::msg::MarkerArray& arr, const std::vector<std::string>& link_names,
1188  bool include_attached) const
1189 {
1190  rclcpp::Clock clock;
1191  for (const std::string& link_name : link_names)
1192  {
1193  RCLCPP_DEBUG(LOGGER, "Trying to get marker for link '%s'", link_name.c_str());
1194  const LinkModel* link_model = robot_model_->getLinkModel(link_name);
1195  if (!link_model)
1196  continue;
1197  if (include_attached)
1198  for (const auto& it : attached_body_map_)
1199  if (it.second->getAttachedLink() == link_model)
1200  {
1201  for (std::size_t j = 0; j < it.second->getShapes().size(); ++j)
1202  {
1203  visualization_msgs::msg::Marker att_mark;
1204  att_mark.header.frame_id = robot_model_->getModelFrame();
1205  att_mark.header.stamp = clock.now();
1206  if (shapes::constructMarkerFromShape(it.second->getShapes()[j].get(), att_mark))
1207  {
1208  // if the object is invisible (0 volume) we skip it
1209  if (fabs(att_mark.scale.x * att_mark.scale.y * att_mark.scale.z) < std::numeric_limits<float>::epsilon())
1210  continue;
1211  att_mark.pose = tf2::toMsg(it.second->getGlobalCollisionBodyTransforms()[j]);
1212  arr.markers.push_back(att_mark);
1213  }
1214  }
1215  }
1216 
1217  if (link_model->getShapes().empty())
1218  continue;
1219 
1220  for (std::size_t j = 0; j < link_model->getShapes().size(); ++j)
1221  {
1222  visualization_msgs::msg::Marker mark;
1223  mark.header.frame_id = robot_model_->getModelFrame();
1224  mark.header.stamp = clock.now();
1225 
1226  // we prefer using the visual mesh, if a mesh is available and we have one body to render
1227  const std::string& mesh_resource = link_model->getVisualMeshFilename();
1228  if (mesh_resource.empty() || link_model->getShapes().size() > 1)
1229  {
1230  if (!shapes::constructMarkerFromShape(link_model->getShapes()[j].get(), mark))
1231  continue;
1232  // if the object is invisible (0 volume) we skip it
1233  if (fabs(mark.scale.x * mark.scale.y * mark.scale.z) < std::numeric_limits<float>::epsilon())
1234  continue;
1235  mark.pose =
1236  tf2::toMsg(global_collision_body_transforms_[link_model->getFirstCollisionBodyTransformIndex() + j]);
1237  }
1238  else
1239  {
1240  mark.type = mark.MESH_RESOURCE;
1241  mark.mesh_use_embedded_materials = false;
1242  mark.mesh_resource = mesh_resource;
1243  const Eigen::Vector3d& mesh_scale = link_model->getVisualMeshScale();
1244 
1245  mark.scale.x = mesh_scale[0];
1246  mark.scale.y = mesh_scale[1];
1247  mark.scale.z = mesh_scale[2];
1248  mark.pose = tf2::toMsg(global_link_transforms_[link_model->getLinkIndex()] * link_model->getVisualMeshOrigin());
1249  }
1250 
1251  arr.markers.push_back(mark);
1252  }
1253  }
1254 }
1255 
1257  const Eigen::Vector3d& reference_point_position) const
1258 {
1259  Eigen::MatrixXd result;
1260  if (!getJacobian(group, group->getLinkModels().back(), reference_point_position, result, false))
1261  throw Exception("Unable to compute Jacobian");
1262  return result;
1263 }
1264 
1266  const Eigen::Vector3d& reference_point_position, Eigen::MatrixXd& jacobian,
1267  bool use_quaternion_representation) const
1268 {
1269  assert(checkLinkTransforms());
1270 
1271  if (!group->isChain())
1272  {
1273  RCLCPP_ERROR(LOGGER, "The group '%s' is not a chain. Cannot compute Jacobian.", group->getName().c_str());
1274  return false;
1275  }
1276 
1277  if (!group->isLinkUpdated(link->getName()))
1278  {
1279  RCLCPP_ERROR(LOGGER, "Link name '%s' does not exist in the chain '%s' or is not a child for this chain",
1280  link->getName().c_str(), group->getName().c_str());
1281  return false;
1282  }
1283 
1284  const moveit::core::JointModel* root_joint_model = group->getJointModels()[0]; // group->getJointRoots()[0];
1285  const moveit::core::LinkModel* root_link_model = root_joint_model->getParentLinkModel();
1286  // getGlobalLinkTransform() returns a valid isometry by contract
1287  Eigen::Isometry3d reference_transform =
1288  root_link_model ? getGlobalLinkTransform(root_link_model).inverse() : Eigen::Isometry3d::Identity();
1289  int rows = use_quaternion_representation ? 7 : 6;
1290  int columns = group->getVariableCount();
1291  jacobian = Eigen::MatrixXd::Zero(rows, columns);
1292 
1293  // getGlobalLinkTransform() returns a valid isometry by contract
1294  Eigen::Isometry3d link_transform = reference_transform * getGlobalLinkTransform(link); // valid isometry
1295  Eigen::Vector3d point_transform = link_transform * reference_point_position;
1296 
1297  // RCLCPP_DEBUG(LOGGER, "Point from reference origin expressed in world coordinates: %f %f %f",
1298  // point_transform.x(),
1299  // point_transform.y(),
1300  // point_transform.z());
1301 
1302  Eigen::Vector3d joint_axis;
1303  Eigen::Isometry3d joint_transform;
1304 
1305  while (link)
1306  {
1307  // RCLCPP_DEBUG(LOGGER, "Link: %s, %f %f %f",link_state->getName().c_str(),
1308  // link_state->getGlobalLinkTransform().translation().x(),
1309  // link_state->getGlobalLinkTransform().translation().y(),
1310  // link_state->getGlobalLinkTransform().translation().z());
1311  // RCLCPP_DEBUG(LOGGER, "Joint: %s",link_state->getParentJointState()->getName().c_str());
1312 
1313  const JointModel* pjm = link->getParentJointModel();
1314  if (pjm->getVariableCount() > 0)
1315  {
1316  if (!group->hasJointModel(pjm->getName()))
1317  {
1318  link = pjm->getParentLinkModel();
1319  continue;
1320  }
1321  unsigned int joint_index = group->getVariableGroupIndex(pjm->getName());
1322  // getGlobalLinkTransform() returns a valid isometry by contract
1323  joint_transform = reference_transform * getGlobalLinkTransform(link); // valid isometry
1325  {
1326  joint_axis = joint_transform.linear() * static_cast<const moveit::core::RevoluteJointModel*>(pjm)->getAxis();
1327  jacobian.block<3, 1>(0, joint_index) =
1328  jacobian.block<3, 1>(0, joint_index) + joint_axis.cross(point_transform - joint_transform.translation());
1329  jacobian.block<3, 1>(3, joint_index) = jacobian.block<3, 1>(3, joint_index) + joint_axis;
1330  }
1331  else if (pjm->getType() == moveit::core::JointModel::PRISMATIC)
1332  {
1333  joint_axis = joint_transform.linear() * static_cast<const moveit::core::PrismaticJointModel*>(pjm)->getAxis();
1334  jacobian.block<3, 1>(0, joint_index) = jacobian.block<3, 1>(0, joint_index) + joint_axis;
1335  }
1336  else if (pjm->getType() == moveit::core::JointModel::PLANAR)
1337  {
1338  joint_axis = joint_transform * Eigen::Vector3d(1.0, 0.0, 0.0);
1339  jacobian.block<3, 1>(0, joint_index) = jacobian.block<3, 1>(0, joint_index) + joint_axis;
1340  joint_axis = joint_transform * Eigen::Vector3d(0.0, 1.0, 0.0);
1341  jacobian.block<3, 1>(0, joint_index + 1) = jacobian.block<3, 1>(0, joint_index + 1) + joint_axis;
1342  joint_axis = joint_transform * Eigen::Vector3d(0.0, 0.0, 1.0);
1343  jacobian.block<3, 1>(0, joint_index + 2) = jacobian.block<3, 1>(0, joint_index + 2) +
1344  joint_axis.cross(point_transform - joint_transform.translation());
1345  jacobian.block<3, 1>(3, joint_index + 2) = jacobian.block<3, 1>(3, joint_index + 2) + joint_axis;
1346  }
1347  else
1348  RCLCPP_ERROR(LOGGER, "Unknown type of joint in Jacobian computation");
1349  }
1350  if (pjm == root_joint_model)
1351  break;
1352  link = pjm->getParentLinkModel();
1353  }
1354  if (use_quaternion_representation)
1355  { // Quaternion representation
1356  // From "Advanced Dynamics and Motion Simulation" by Paul Mitiguy
1357  // d/dt ( [w] ) = 1/2 * [ -x -y -z ] * [ omega_1 ]
1358  // [x] [ w -z y ] [ omega_2 ]
1359  // [y] [ z w -x ] [ omega_3 ]
1360  // [z] [ -y x w ]
1361  Eigen::Quaterniond q(link_transform.linear());
1362  double w = q.w(), x = q.x(), y = q.y(), z = q.z();
1363  Eigen::MatrixXd quaternion_update_matrix(4, 3);
1364  quaternion_update_matrix << -x, -y, -z, w, -z, y, z, w, -x, -y, x, w;
1365  jacobian.block(3, 0, 4, columns) = 0.5 * quaternion_update_matrix * jacobian.block(3, 0, 3, columns);
1366  }
1367  return true;
1368 }
1369 
1370 bool RobotState::setFromDiffIK(const JointModelGroup* jmg, const Eigen::VectorXd& twist, const std::string& tip,
1371  double dt, const GroupStateValidityCallbackFn& constraint)
1372 {
1373  Eigen::VectorXd qdot;
1374  computeVariableVelocity(jmg, qdot, twist, getLinkModel(tip));
1375  return integrateVariableVelocity(jmg, qdot, dt, constraint);
1376 }
1377 
1378 bool RobotState::setFromDiffIK(const JointModelGroup* jmg, const geometry_msgs::msg::Twist& twist,
1379  const std::string& tip, double dt, const GroupStateValidityCallbackFn& constraint)
1380 {
1381  Eigen::Matrix<double, 6, 1> t;
1382  tf2::fromMsg(twist, t);
1383  return setFromDiffIK(jmg, t, tip, dt, constraint);
1384 }
1385 
1386 void RobotState::computeVariableVelocity(const JointModelGroup* jmg, Eigen::VectorXd& qdot,
1387  const Eigen::VectorXd& twist, const LinkModel* tip) const
1388 {
1389  // Get the Jacobian of the group at the current configuration
1390  Eigen::MatrixXd j(6, jmg->getVariableCount());
1391  Eigen::Vector3d reference_point(0.0, 0.0, 0.0);
1392  getJacobian(jmg, tip, reference_point, j, false);
1393 
1394  // Rotate the jacobian to the end-effector frame
1395  Eigen::Isometry3d e_mb = getGlobalLinkTransform(tip).inverse();
1396  Eigen::MatrixXd e_wb = Eigen::ArrayXXd::Zero(6, 6);
1397  e_wb.block(0, 0, 3, 3) = e_mb.matrix().block(0, 0, 3, 3);
1398  e_wb.block(3, 3, 3, 3) = e_mb.matrix().block(0, 0, 3, 3);
1399  j = e_wb * j;
1400 
1401  // Do the Jacobian moore-penrose pseudo-inverse
1402  Eigen::JacobiSVD<Eigen::MatrixXd> svd_of_j(j, Eigen::ComputeThinU | Eigen::ComputeThinV);
1403  const Eigen::MatrixXd& u = svd_of_j.matrixU();
1404  const Eigen::MatrixXd& v = svd_of_j.matrixV();
1405  const Eigen::VectorXd& s = svd_of_j.singularValues();
1406 
1407  Eigen::VectorXd sinv = s;
1408  static const double PINVTOLER = std::numeric_limits<float>::epsilon();
1409  double maxsv = 0.0;
1410  for (std::size_t i = 0; i < static_cast<std::size_t>(s.rows()); ++i)
1411  if (fabs(s(i)) > maxsv)
1412  maxsv = fabs(s(i));
1413  for (std::size_t i = 0; i < static_cast<std::size_t>(s.rows()); ++i)
1414  {
1415  // Those singular values smaller than a percentage of the maximum singular value are removed
1416  if (fabs(s(i)) > maxsv * PINVTOLER)
1417  sinv(i) = 1.0 / s(i);
1418  else
1419  sinv(i) = 0.0;
1420  }
1421  Eigen::MatrixXd jinv = (v * sinv.asDiagonal() * u.transpose());
1422 
1423  // Compute joint velocity
1424  qdot = jinv * twist;
1425 }
1426 
1427 bool RobotState::integrateVariableVelocity(const JointModelGroup* jmg, const Eigen::VectorXd& qdot, double dt,
1428  const GroupStateValidityCallbackFn& constraint)
1429 {
1430  Eigen::VectorXd q(jmg->getVariableCount());
1431  copyJointGroupPositions(jmg, q);
1432  q = q + dt * qdot;
1433  setJointGroupPositions(jmg, q);
1434  enforceBounds(jmg);
1435 
1436  if (constraint)
1437  {
1438  std::vector<double> values;
1439  copyJointGroupPositions(jmg, values);
1440  return constraint(this, jmg, &values[0]);
1441  }
1442  else
1443  return true;
1444 }
1445 
1446 bool RobotState::setFromIK(const JointModelGroup* jmg, const geometry_msgs::msg::Pose& pose, double timeout,
1447  const GroupStateValidityCallbackFn& constraint,
1449  const kinematics::KinematicsBase::IKCostFn& cost_function)
1450 {
1451  const kinematics::KinematicsBaseConstPtr& solver = jmg->getSolverInstance();
1452  if (!solver)
1453  {
1454  RCLCPP_ERROR(LOGGER, "No kinematics solver instantiated for group '%s'", jmg->getName().c_str());
1455  return false;
1456  }
1457  return setFromIK(jmg, pose, solver->getTipFrame(), timeout, constraint, options, cost_function);
1458 }
1459 
1460 bool RobotState::setFromIK(const JointModelGroup* jmg, const geometry_msgs::msg::Pose& pose, const std::string& tip,
1461  double timeout, const GroupStateValidityCallbackFn& constraint,
1463  const kinematics::KinematicsBase::IKCostFn& cost_function)
1464 {
1465  Eigen::Isometry3d mat;
1466  tf2::fromMsg(pose, mat);
1467  static std::vector<double> consistency_limits;
1468  return setFromIK(jmg, mat, tip, consistency_limits, timeout, constraint, options, cost_function);
1469 }
1470 
1471 bool RobotState::setFromIK(const JointModelGroup* jmg, const Eigen::Isometry3d& pose, double timeout,
1472  const GroupStateValidityCallbackFn& constraint,
1474  const kinematics::KinematicsBase::IKCostFn& cost_function)
1475 {
1476  const kinematics::KinematicsBaseConstPtr& solver = jmg->getSolverInstance();
1477  if (!solver)
1478  {
1479  RCLCPP_ERROR(LOGGER, "No kinematics solver instantiated for group '%s'", jmg->getName().c_str());
1480  return false;
1481  }
1482  static std::vector<double> consistency_limits;
1483  return setFromIK(jmg, pose, solver->getTipFrame(), consistency_limits, timeout, constraint, options, cost_function);
1484 }
1485 
1486 bool RobotState::setFromIK(const JointModelGroup* jmg, const Eigen::Isometry3d& pose_in, const std::string& tip_in,
1487  double timeout, const GroupStateValidityCallbackFn& constraint,
1489  const kinematics::KinematicsBase::IKCostFn& cost_function)
1490 {
1491  static std::vector<double> consistency_limits;
1492  return setFromIK(jmg, pose_in, tip_in, consistency_limits, timeout, constraint, options, cost_function);
1493 }
1494 
1495 namespace
1496 {
1497 bool ikCallbackFnAdapter(RobotState* state, const JointModelGroup* group,
1498  const GroupStateValidityCallbackFn& constraint, const geometry_msgs::msg::Pose& /*unused*/,
1499  const std::vector<double>& ik_sol, moveit_msgs::msg::MoveItErrorCodes& error_code)
1500 {
1501  const std::vector<size_t>& bij = group->getKinematicsSolverJointBijection();
1502  std::vector<double> solution(bij.size());
1503  for (std::size_t i = 0; i < bij.size(); ++i)
1504  solution[bij[i]] = ik_sol[i];
1505  if (constraint(state, group, &solution[0]))
1506  error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
1507  else
1508  error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
1509  return true;
1510 }
1511 } // namespace
1512 
1513 bool RobotState::setToIKSolverFrame(Eigen::Isometry3d& pose, const kinematics::KinematicsBaseConstPtr& solver)
1514 {
1515  return setToIKSolverFrame(pose, solver->getBaseFrame());
1516 }
1517 
1518 bool RobotState::setToIKSolverFrame(Eigen::Isometry3d& pose, const std::string& ik_frame)
1519 {
1520  // Bring the pose to the frame of the IK solver
1521  if (!Transforms::sameFrame(ik_frame, robot_model_->getModelFrame()))
1522  {
1523  const LinkModel* link_model =
1524  getLinkModel((!ik_frame.empty() && ik_frame[0] == '/') ? ik_frame.substr(1) : ik_frame);
1525  if (!link_model)
1526  {
1527  RCLCPP_ERROR(LOGGER, "The following IK frame does not exist: %s", ik_frame.c_str());
1528  return false;
1529  }
1530  pose = getGlobalLinkTransform(link_model).inverse() * pose;
1531  }
1532  return true;
1533 }
1534 
1535 bool RobotState::setFromIK(const JointModelGroup* jmg, const Eigen::Isometry3d& pose_in, const std::string& tip_in,
1536  const std::vector<double>& consistency_limits_in, double timeout,
1537  const GroupStateValidityCallbackFn& constraint,
1539  const kinematics::KinematicsBase::IKCostFn& cost_function)
1540 {
1541  // Convert from single pose and tip to vectors
1542  EigenSTL::vector_Isometry3d poses;
1543  poses.push_back(pose_in);
1544 
1545  std::vector<std::string> tips;
1546  tips.push_back(tip_in);
1547 
1548  std::vector<std::vector<double> > consistency_limits;
1549  consistency_limits.push_back(consistency_limits_in);
1550 
1551  return setFromIK(jmg, poses, tips, consistency_limits, timeout, constraint, options, cost_function);
1552 }
1553 
1554 bool RobotState::setFromIK(const JointModelGroup* jmg, const EigenSTL::vector_Isometry3d& poses_in,
1555  const std::vector<std::string>& tips_in, double timeout,
1556  const GroupStateValidityCallbackFn& constraint,
1558  const kinematics::KinematicsBase::IKCostFn& cost_function)
1559 {
1560  const std::vector<std::vector<double> > consistency_limits;
1561  return setFromIK(jmg, poses_in, tips_in, consistency_limits, timeout, constraint, options, cost_function);
1562 }
1563 
1564 bool RobotState::setFromIK(const JointModelGroup* jmg, const EigenSTL::vector_Isometry3d& poses_in,
1565  const std::vector<std::string>& tips_in,
1566  const std::vector<std::vector<double> >& consistency_limit_sets, double timeout,
1567  const GroupStateValidityCallbackFn& constraint,
1569  const kinematics::KinematicsBase::IKCostFn& cost_function)
1570 {
1571  // Error check
1572  if (poses_in.size() != tips_in.size())
1573  {
1574  RCLCPP_ERROR(LOGGER, "Number of poses must be the same as number of tips");
1575  return false;
1576  }
1577 
1578  // Load solver
1579  const kinematics::KinematicsBaseConstPtr& solver = jmg->getSolverInstance();
1580 
1581  // Check if this jmg has a solver
1582  bool valid_solver = true;
1583  if (!solver)
1584  {
1585  valid_solver = false;
1586  }
1587  // Check if this jmg's IK solver can handle multiple tips (non-chain solver)
1588  else if (poses_in.size() > 1)
1589  {
1590  std::string error_msg;
1591  if (!solver->supportsGroup(jmg, &error_msg))
1592  {
1593  const kinematics::KinematicsBase& solver_ref = *solver;
1594  RCLCPP_ERROR(LOGGER, "Kinematics solver %s does not support joint group %s. Error: %s",
1595  typeid(solver_ref).name(), jmg->getName().c_str(), error_msg.c_str());
1596  valid_solver = false;
1597  }
1598  }
1599 
1600  if (!valid_solver)
1601  {
1602  // Check if there are subgroups that can solve this for us (non-chains)
1603  if (poses_in.size() > 1)
1604  {
1605  // Forward to setFromIKSubgroups() to allow different subgroup IK solvers to work together
1606  return setFromIKSubgroups(jmg, poses_in, tips_in, consistency_limit_sets, timeout, constraint, options);
1607  }
1608  else
1609  {
1610  RCLCPP_ERROR(LOGGER, "No kinematics solver instantiated for group '%s'", jmg->getName().c_str());
1611  return false;
1612  }
1613  }
1614 
1615  // Check that no, or only one set of consistency limits has been passed in, and choose that one
1616  std::vector<double> consistency_limits;
1617  if (consistency_limit_sets.size() > 1)
1618  {
1619  RCLCPP_ERROR(LOGGER,
1620  "Invalid number (%zu) of sets of consistency limits for a setFromIK request "
1621  "that is being solved by a single IK solver",
1622  consistency_limit_sets.size());
1623  return false;
1624  }
1625  else if (consistency_limit_sets.size() == 1)
1626  consistency_limits = consistency_limit_sets[0];
1627 
1628  const std::vector<std::string>& solver_tip_frames = solver->getTipFrames();
1629 
1630  // Track which possible tips frames we have filled in so far
1631  std::vector<bool> tip_frames_used(solver_tip_frames.size(), false);
1632 
1633  // Create vector to hold the output frames in the same order as solver_tip_frames
1634  std::vector<geometry_msgs::msg::Pose> ik_queries(solver_tip_frames.size());
1635 
1636  // Bring each pose to the frame of the IK solver
1637  for (std::size_t i = 0; i < poses_in.size(); ++i)
1638  {
1639  // Make non-const
1640  Eigen::Isometry3d pose = poses_in[i];
1641  std::string pose_frame = tips_in[i];
1642 
1643  // Remove extra slash
1644  if (!pose_frame.empty() && pose_frame[0] == '/')
1645  pose_frame = pose_frame.substr(1);
1646 
1647  // bring the pose to the frame of the IK solver
1648  if (!setToIKSolverFrame(pose, solver))
1649  return false;
1650 
1651  // try all of the solver's possible tip frames to see if they uniquely align with any of our passed in pose tip
1652  // frames
1653  bool found_valid_frame = false;
1654  std::size_t solver_tip_id; // our current index
1655  for (solver_tip_id = 0; solver_tip_id < solver_tip_frames.size(); ++solver_tip_id)
1656  {
1657  // Check if this tip frame is already accounted for
1658  if (tip_frames_used[solver_tip_id])
1659  continue; // already has a pose
1660 
1661  // check if the tip frame can be transformed via fixed transforms to the frame known to the IK solver
1662  std::string solver_tip_frame = solver_tip_frames[solver_tip_id];
1663 
1664  // remove the frame '/' if there is one, so we can avoid calling Transforms::sameFrame() which may copy strings
1665  // more often that we need to
1666  if (!solver_tip_frame.empty() && solver_tip_frame[0] == '/')
1667  solver_tip_frame = solver_tip_frame.substr(1);
1668 
1669  if (pose_frame != solver_tip_frame)
1670  {
1671  auto* pose_parent = getRigidlyConnectedParentLinkModel(pose_frame);
1672  if (!pose_parent)
1673  {
1674  RCLCPP_ERROR_STREAM(LOGGER, "The following Pose Frame does not exist: " << pose_frame);
1675  return false;
1676  }
1677  Eigen::Isometry3d pose_parent_to_frame = getFrameTransform(pose_frame);
1678  auto* tip_parent = getRigidlyConnectedParentLinkModel(solver_tip_frame);
1679  if (!tip_parent)
1680  {
1681  RCLCPP_ERROR_STREAM(LOGGER, "The following Solver Tip Frame does not exist: " << solver_tip_frame);
1682  return false;
1683  }
1684  Eigen::Isometry3d tip_parent_to_tip = getFrameTransform(solver_tip_frame);
1685  if (pose_parent == tip_parent)
1686  {
1687  // transform goal pose as target for solver_tip_frame (instead of pose_frame)
1688  pose = pose * pose_parent_to_frame.inverse() * tip_parent_to_tip;
1689  found_valid_frame = true;
1690  break;
1691  }
1692  }
1693  else
1694  {
1695  found_valid_frame = true;
1696  break;
1697  } // end if pose_frame
1698  } // end for solver_tip_frames
1699 
1700  // Make sure one of the tip frames worked
1701  if (!found_valid_frame)
1702  {
1703  RCLCPP_ERROR(LOGGER, "Cannot compute IK for query %zu pose reference frame '%s'", i, pose_frame.c_str());
1704  // Debug available tip frames
1705  std::stringstream ss;
1706  for (solver_tip_id = 0; solver_tip_id < solver_tip_frames.size(); ++solver_tip_id)
1707  ss << solver_tip_frames[solver_tip_id] << ", ";
1708  RCLCPP_ERROR(LOGGER, "Available tip frames: [%s]", ss.str().c_str());
1709  return false;
1710  }
1711 
1712  // Remove that tip from the list of available tip frames because each can only have one pose
1713  tip_frames_used[solver_tip_id] = true;
1714 
1715  // Convert Eigen pose to geometry_msgs pose
1716  geometry_msgs::msg::Pose ik_query;
1717  ik_query = tf2::toMsg(pose);
1718 
1719  // Save into vectors
1720  ik_queries[solver_tip_id] = ik_query;
1721  } // end for poses_in
1722 
1723  // Create poses for all remaining tips a solver expects, even if not passed into this function
1724  for (std::size_t solver_tip_id = 0; solver_tip_id < solver_tip_frames.size(); ++solver_tip_id)
1725  {
1726  // Check if this tip frame is already accounted for
1727  if (tip_frames_used[solver_tip_id])
1728  continue; // already has a pose
1729 
1730  // Process this tip
1731  std::string solver_tip_frame = solver_tip_frames[solver_tip_id];
1732 
1733  // remove the frame '/' if there is one, so we can avoid calling Transforms::sameFrame() which may copy strings more
1734  // often that we need to
1735  if (!solver_tip_frame.empty() && solver_tip_frame[0] == '/')
1736  solver_tip_frame = solver_tip_frame.substr(1);
1737 
1738  // Get the pose of a different EE tip link
1739  Eigen::Isometry3d current_pose = getGlobalLinkTransform(solver_tip_frame);
1740 
1741  // bring the pose to the frame of the IK solver
1742  if (!setToIKSolverFrame(current_pose, solver))
1743  return false;
1744 
1745  // Convert Eigen pose to geometry_msgs pose
1746  geometry_msgs::msg::Pose ik_query;
1747  ik_query = tf2::toMsg(current_pose);
1748 
1749  // Save into vectors - but this needs to be ordered in the same order as the IK solver expects its tip frames
1750  ik_queries[solver_tip_id] = ik_query;
1751 
1752  // Remove that tip from the list of available tip frames because each can only have one pose
1753  tip_frames_used[solver_tip_id] = true;
1754  }
1755 
1756  // if no timeout has been specified, use the default one
1757  if (timeout < std::numeric_limits<double>::epsilon())
1758  timeout = jmg->getDefaultIKTimeout();
1759 
1760  // set callback function
1762  if (constraint)
1763  ik_callback_fn = ik_callback_fn = [this, jmg, constraint](const geometry_msgs::msg::Pose& pose,
1764  const std::vector<double>& joints,
1765  moveit_msgs::msg::MoveItErrorCodes& error_code) {
1766  ikCallbackFnAdapter(this, jmg, constraint, pose, joints, error_code);
1767  };
1768 
1769  // Bijection
1770  const std::vector<size_t>& bij = jmg->getKinematicsSolverJointBijection();
1771 
1772  std::vector<double> initial_values;
1773  copyJointGroupPositions(jmg, initial_values);
1774  std::vector<double> seed(bij.size());
1775  for (std::size_t i = 0; i < bij.size(); ++i)
1776  seed[i] = initial_values[bij[i]];
1777 
1778  // compute the IK solution
1779  std::vector<double> ik_sol;
1780  moveit_msgs::msg::MoveItErrorCodes error;
1781 
1782  if (solver->searchPositionIK(ik_queries, seed, timeout, consistency_limits, ik_sol, ik_callback_fn, cost_function,
1783  error, options, this))
1784  {
1785  std::vector<double> solution(bij.size());
1786  for (std::size_t i = 0; i < bij.size(); ++i)
1787  solution[bij[i]] = ik_sol[i];
1788  setJointGroupPositions(jmg, solution);
1789  return true;
1790  }
1791  return false;
1792 }
1793 
1794 bool RobotState::setFromIKSubgroups(const JointModelGroup* jmg, const EigenSTL::vector_Isometry3d& poses_in,
1795  const std::vector<std::string>& tips_in,
1796  const std::vector<std::vector<double> >& consistency_limits, double timeout,
1797  const GroupStateValidityCallbackFn& constraint,
1798  const kinematics::KinematicsQueryOptions& /*options*/)
1799 {
1800  // Assume we have already ran setFromIK() and those checks
1801 
1802  // Get containing subgroups
1803  std::vector<const JointModelGroup*> sub_groups;
1804  jmg->getSubgroups(sub_groups);
1805 
1806  // Error check
1807  if (poses_in.size() != sub_groups.size())
1808  {
1809  RCLCPP_ERROR(LOGGER, "Number of poses (%zu) must be the same as number of sub-groups (%zu)", poses_in.size(),
1810  sub_groups.size());
1811  return false;
1812  }
1813 
1814  if (tips_in.size() != sub_groups.size())
1815  {
1816  RCLCPP_ERROR(LOGGER, "Number of tip names (%zu) must be same as number of sub-groups (%zu)", tips_in.size(),
1817  sub_groups.size());
1818  return false;
1819  }
1820 
1821  if (!consistency_limits.empty() && consistency_limits.size() != sub_groups.size())
1822  {
1823  RCLCPP_ERROR(LOGGER, "Number of consistency limit vectors must be the same as number of sub-groups");
1824  return false;
1825  }
1826 
1827  for (std::size_t i = 0; i < consistency_limits.size(); ++i)
1828  {
1829  if (consistency_limits[i].size() != sub_groups[i]->getVariableCount())
1830  {
1831  RCLCPP_ERROR(LOGGER, "Number of joints in consistency_limits is %zu but it should be should be %u", i,
1832  sub_groups[i]->getVariableCount());
1833  return false;
1834  }
1835  }
1836 
1837  // Populate list of kin solvers for the various subgroups
1838  std::vector<kinematics::KinematicsBaseConstPtr> solvers;
1839  for (std::size_t i = 0; i < poses_in.size(); ++i)
1840  {
1841  kinematics::KinematicsBaseConstPtr solver = sub_groups[i]->getSolverInstance();
1842  if (!solver)
1843  {
1844  RCLCPP_ERROR(LOGGER, "Could not find solver for group '%s'", sub_groups[i]->getName().c_str());
1845  return false;
1846  }
1847  solvers.push_back(solver);
1848  }
1849 
1850  // Make non-const versions
1851  EigenSTL::vector_Isometry3d transformed_poses = poses_in;
1852  std::vector<std::string> pose_frames = tips_in;
1853 
1854  // Each each pose's tip frame naming
1855  for (std::size_t i = 0; i < poses_in.size(); ++i)
1856  {
1857  ASSERT_ISOMETRY(transformed_poses[i]) // unsanitized input, could contain a non-isometry
1858  Eigen::Isometry3d& pose = transformed_poses[i];
1859  std::string& pose_frame = pose_frames[i];
1860 
1861  // bring the pose to the frame of the IK solver
1862  if (!setToIKSolverFrame(pose, solvers[i]))
1863  return false;
1864 
1865  // see if the tip frame can be transformed via fixed transforms to the frame known to the IK solver
1866  std::string solver_tip_frame = solvers[i]->getTipFrame();
1867 
1868  // remove the frame '/' if there is one, so we can avoid calling Transforms::sameFrame() which may copy strings more
1869  // often that we need to
1870  if (!solver_tip_frame.empty() && solver_tip_frame[0] == '/')
1871  solver_tip_frame = solver_tip_frame.substr(1);
1872 
1873  if (pose_frame != solver_tip_frame)
1874  {
1875  if (hasAttachedBody(pose_frame))
1876  {
1877  const AttachedBody* body = getAttachedBody(pose_frame);
1878  pose_frame = body->getAttachedLinkName();
1879  pose = pose * body->getPose().inverse(); // valid isometry
1880  }
1881  if (pose_frame != solver_tip_frame)
1882  {
1883  const moveit::core::LinkModel* link_model = getLinkModel(pose_frame);
1884  if (!link_model)
1885  return false;
1886  // getAssociatedFixedTransforms() returns valid isometries by contract
1887  const moveit::core::LinkTransformMap& fixed_links = link_model->getAssociatedFixedTransforms();
1888  for (const std::pair<const LinkModel* const, Eigen::Isometry3d>& fixed_link : fixed_links)
1889  if (fixed_link.first->getName() == solver_tip_frame)
1890  {
1891  pose_frame = solver_tip_frame;
1892  pose = pose * fixed_link.second; // valid isometry
1893  break;
1894  }
1895  }
1896  }
1897 
1898  if (pose_frame != solver_tip_frame)
1899  {
1900  RCLCPP_ERROR(LOGGER, "Cannot compute IK for query pose reference frame '%s', desired: '%s'", pose_frame.c_str(),
1901  solver_tip_frame.c_str());
1902  return false;
1903  }
1904  }
1905 
1906  // Convert Eigen poses to geometry_msg format
1907  std::vector<geometry_msgs::msg::Pose> ik_queries(poses_in.size());
1909  if (constraint)
1910  ik_callback_fn = [this, jmg, constraint](const geometry_msgs::msg::Pose pose, const std::vector<double>& joints,
1911  moveit_msgs::msg::MoveItErrorCodes& error_code) {
1912  ikCallbackFnAdapter(this, jmg, constraint, pose, joints, error_code);
1913  };
1914 
1915  for (std::size_t i = 0; i < transformed_poses.size(); ++i)
1916  {
1917  Eigen::Quaterniond quat(transformed_poses[i].linear());
1918  Eigen::Vector3d point(transformed_poses[i].translation());
1919  ik_queries[i].position.x = point.x();
1920  ik_queries[i].position.y = point.y();
1921  ik_queries[i].position.z = point.z();
1922  ik_queries[i].orientation.x = quat.x();
1923  ik_queries[i].orientation.y = quat.y();
1924  ik_queries[i].orientation.z = quat.z();
1925  ik_queries[i].orientation.w = quat.w();
1926  }
1927 
1928  // if no timeout has been specified, use the default one
1929  if (timeout < std::numeric_limits<double>::epsilon())
1930  timeout = jmg->getDefaultIKTimeout();
1931 
1932  auto start = std::chrono::system_clock::now();
1933  double elapsed = 0;
1934 
1935  bool first_seed = true;
1936  unsigned int attempts = 0;
1937  do
1938  {
1939  ++attempts;
1940  RCLCPP_DEBUG(LOGGER, "IK attempt: %d", attempts);
1941  bool found_solution = true;
1942  for (std::size_t sg = 0; sg < sub_groups.size(); ++sg)
1943  {
1944  const std::vector<size_t>& bij = sub_groups[sg]->getKinematicsSolverJointBijection();
1945  std::vector<double> seed(bij.size());
1946  // the first seed is the initial state
1947  if (first_seed)
1948  {
1949  std::vector<double> initial_values;
1950  copyJointGroupPositions(sub_groups[sg], initial_values);
1951  for (std::size_t i = 0; i < bij.size(); ++i)
1952  seed[i] = initial_values[bij[i]];
1953  }
1954  else
1955  {
1956  // sample a random seed
1957  random_numbers::RandomNumberGenerator& rng = getRandomNumberGenerator();
1958  std::vector<double> random_values;
1959  sub_groups[sg]->getVariableRandomPositions(rng, random_values);
1960  for (std::size_t i = 0; i < bij.size(); ++i)
1961  seed[i] = random_values[bij[i]];
1962  }
1963 
1964  // compute the IK solution
1965  std::vector<double> ik_sol;
1966  moveit_msgs::msg::MoveItErrorCodes error;
1967  const std::vector<double>& climits = consistency_limits.empty() ? std::vector<double>() : consistency_limits[sg];
1968  if (solvers[sg]->searchPositionIK(ik_queries[sg], seed, (timeout - elapsed) / sub_groups.size(), climits, ik_sol,
1969  error))
1970  {
1971  std::vector<double> solution(bij.size());
1972  for (std::size_t i = 0; i < bij.size(); ++i)
1973  solution[bij[i]] = ik_sol[i];
1974  setJointGroupPositions(sub_groups[sg], solution);
1975  }
1976  else
1977  {
1978  found_solution = false;
1979  break;
1980  }
1981  }
1982  if (found_solution)
1983  {
1984  std::vector<double> full_solution;
1985  copyJointGroupPositions(jmg, full_solution);
1986  if (constraint ? constraint(this, jmg, &full_solution[0]) : true)
1987  {
1988  RCLCPP_DEBUG(LOGGER, "Found IK solution");
1989  return true;
1990  }
1991  }
1992  elapsed = std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - start).count();
1993  first_seed = false;
1994  } while (elapsed < timeout);
1995  return false;
1996 }
1997 
1998 double RobotState::computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
1999  const LinkModel* link, const Eigen::Vector3d& direction,
2000  bool global_reference_frame, double distance, double max_step,
2001  double jump_threshold_factor, const GroupStateValidityCallbackFn& validCallback,
2003 {
2004  return CartesianInterpolator::computeCartesianPath(this, group, traj, link, direction, global_reference_frame,
2005  distance, MaxEEFStep(max_step),
2006  JumpThreshold(jump_threshold_factor), validCallback, options);
2007 }
2008 
2009 double RobotState::computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
2010  const LinkModel* link, const Eigen::Isometry3d& target,
2011  bool global_reference_frame, double max_step, double jump_threshold_factor,
2012  const GroupStateValidityCallbackFn& validCallback,
2014 {
2015  return CartesianInterpolator::computeCartesianPath(this, group, traj, link, target, global_reference_frame,
2016  MaxEEFStep(max_step), JumpThreshold(jump_threshold_factor),
2017  validCallback, options);
2018 }
2019 
2020 double RobotState::computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
2021  const LinkModel* link, const EigenSTL::vector_Isometry3d& waypoints,
2022  bool global_reference_frame, double max_step, double jump_threshold_factor,
2023  const GroupStateValidityCallbackFn& validCallback,
2025 {
2026  return CartesianInterpolator::computeCartesianPath(this, group, traj, link, waypoints, global_reference_frame,
2027  MaxEEFStep(max_step), JumpThreshold(jump_threshold_factor),
2028  validCallback, options);
2029 }
2030 
2031 void RobotState::computeAABB(std::vector<double>& aabb) const
2032 {
2033  assert(checkLinkTransforms());
2034 
2035  core::AABB bounding_box;
2036  std::vector<const LinkModel*> links = robot_model_->getLinkModelsWithCollisionGeometry();
2037  for (const LinkModel* link : links)
2038  {
2039  Eigen::Isometry3d transform = getGlobalLinkTransform(link); // intentional copy, we will translate
2040  const Eigen::Vector3d& extents = link->getShapeExtentsAtOrigin();
2041  transform.translate(link->getCenteredBoundingBoxOffset());
2042  bounding_box.extendWithTransformedBox(transform, extents);
2043  }
2044  for (const auto& it : attached_body_map_)
2045  {
2046  const EigenSTL::vector_Isometry3d& transforms = it.second->getGlobalCollisionBodyTransforms();
2047  const std::vector<shapes::ShapeConstPtr>& shapes = it.second->getShapes();
2048  for (std::size_t i = 0; i < transforms.size(); ++i)
2049  {
2050  Eigen::Vector3d extents = shapes::computeShapeExtents(shapes[i].get());
2051  bounding_box.extendWithTransformedBox(transforms[i], extents);
2052  }
2053  }
2054 
2055  aabb.clear();
2056  aabb.resize(6, 0.0);
2057  if (!bounding_box.isEmpty())
2058  {
2059  // The following is a shorthand for something like:
2060  // aabb[0, 2, 4] = bounding_box.min(); aabb[1, 3, 5] = bounding_box.max();
2061  Eigen::Map<Eigen::VectorXd, Eigen::Unaligned, Eigen::InnerStride<2> >(aabb.data(), 3) = bounding_box.min();
2062  Eigen::Map<Eigen::VectorXd, Eigen::Unaligned, Eigen::InnerStride<2> >(aabb.data() + 1, 3) = bounding_box.max();
2063  }
2064 }
2065 
2066 void RobotState::printStatePositions(std::ostream& out) const
2067 {
2068  const std::vector<std::string>& nm = robot_model_->getVariableNames();
2069  for (std::size_t i = 0; i < nm.size(); ++i)
2070  out << nm[i] << "=" << position_[i] << '\n';
2071 }
2072 
2074 {
2075  // TODO(davetcoleman): support joints with multiple variables / multiple DOFs such as floating joints
2076  // TODO(davetcoleman): support unbounded joints
2077 
2078  const std::vector<const moveit::core::JointModel*>& joints = jmg->getActiveJointModels();
2079 
2080  // Loop through joints
2081  for (const JointModel* joint : joints)
2082  {
2083  // Ignore joints with more than one variable
2084  if (joint->getVariableCount() > 1)
2085  continue;
2086 
2087  double current_value = getVariablePosition(joint->getName());
2088 
2089  // check if joint is beyond limits
2090  bool out_of_bounds = !satisfiesBounds(joint);
2091 
2092  const moveit::core::VariableBounds& bound = joint->getVariableBounds()[0];
2093 
2094  if (out_of_bounds)
2095  out << MOVEIT_CONSOLE_COLOR_RED;
2096 
2097  out << " " << std::fixed << std::setprecision(5) << bound.min_position_ << "\t";
2098  double delta = bound.max_position_ - bound.min_position_;
2099  double step = delta / 20.0;
2100 
2101  bool marker_shown = false;
2102  for (double value = bound.min_position_; value < bound.max_position_; value += step)
2103  {
2104  // show marker of current value
2105  if (!marker_shown && current_value < value)
2106  {
2107  out << "|";
2108  marker_shown = true;
2109  }
2110  else
2111  out << "-";
2112  }
2113  if (!marker_shown)
2114  out << "|";
2115 
2116  // show max position
2117  out << " \t" << std::fixed << std::setprecision(5) << bound.max_position_ << " \t" << joint->getName()
2118  << " current: " << std::fixed << std::setprecision(5) << current_value << '\n';
2119 
2120  if (out_of_bounds)
2122  }
2123 }
2124 
2125 void RobotState::printDirtyInfo(std::ostream& out) const
2126 {
2127  out << " * Dirty Joint Transforms: \n";
2128  const std::vector<const JointModel*>& jm = robot_model_->getJointModels();
2129  for (const JointModel* joint : jm)
2130  if (joint->getVariableCount() > 0 && dirtyJointTransform(joint))
2131  out << " " << joint->getName() << '\n';
2132  out << " * Dirty Link Transforms: " << (dirty_link_transforms_ ? dirty_link_transforms_->getName() : "NULL") << '\n';
2133  out << " * Dirty Collision Body Transforms: "
2134  << (dirty_collision_body_transforms_ ? dirty_collision_body_transforms_->getName() : "NULL\n");
2135 }
2136 
2137 void RobotState::printStateInfo(std::ostream& out) const
2138 {
2139  out << "Robot State @" << this << '\n';
2140 
2141  std::size_t n = robot_model_->getVariableCount();
2142  if (position_)
2143  {
2144  out << " * Position: ";
2145  for (std::size_t i = 0; i < n; ++i)
2146  out << position_[i] << " ";
2147  out << '\n';
2148  }
2149  else
2150  out << " * Position: NULL\n";
2151 
2152  if (velocity_)
2153  {
2154  out << " * Velocity: ";
2155  for (std::size_t i = 0; i < n; ++i)
2156  out << velocity_[i] << " ";
2157  out << '\n';
2158  }
2159  else
2160  out << " * Velocity: NULL\n";
2161 
2162  if (acceleration_)
2163  {
2164  out << " * Acceleration: ";
2165  for (std::size_t i = 0; i < n; ++i)
2166  out << acceleration_[i] << " ";
2167  out << '\n';
2168  }
2169  else
2170  out << " * Acceleration: NULL\n";
2171 
2172  out << " * Dirty Link Transforms: " << (dirty_link_transforms_ ? dirty_link_transforms_->getName() : "NULL\n");
2173  out << " * Dirty Collision Body Transforms: "
2174  << (dirty_collision_body_transforms_ ? dirty_collision_body_transforms_->getName() : "NULL\n");
2175 
2176  printTransforms(out);
2177 }
2178 
2179 void RobotState::printTransform(const Eigen::Isometry3d& transform, std::ostream& out) const
2180 {
2181  if (checkIsometry(transform, CHECK_ISOMETRY_PRECISION, false))
2182  {
2183  Eigen::Quaterniond q(transform.linear());
2184  out << "T.xyz = [" << transform.translation().x() << ", " << transform.translation().y() << ", "
2185  << transform.translation().z() << "], Q.xyzw = [" << q.x() << ", " << q.y() << ", " << q.z() << ", " << q.w()
2186  << "]";
2187  }
2188  else
2189  {
2190  out << "[NON-ISOMETRY] "
2191  << transform.matrix().format(
2192  Eigen::IOFormat(Eigen::StreamPrecision, Eigen::DontAlignCols, ", ", "; ", "", "", "[", "]"));
2193  }
2194  out << "\n";
2195 }
2196 
2197 void RobotState::printTransforms(std::ostream& out) const
2198 {
2199  if (!variable_joint_transforms_)
2200  {
2201  out << "No transforms computed\n";
2202  return;
2203  }
2204 
2205  out << "Joint transforms:\n";
2206  const std::vector<const JointModel*>& jm = robot_model_->getJointModels();
2207  for (const JointModel* joint : jm)
2208  {
2209  out << " " << joint->getName();
2210  const int idx = joint->getJointIndex();
2211  if (dirty_joint_transforms_[idx])
2212  out << " [dirty]";
2213  out << ": ";
2214  printTransform(variable_joint_transforms_[idx], out);
2215  }
2216 
2217  out << "Link poses:\n";
2218  const std::vector<const LinkModel*>& link_model = robot_model_->getLinkModels();
2219  for (const LinkModel* link : link_model)
2220  {
2221  out << " " << link->getName() << ": ";
2222  printTransform(global_link_transforms_[link->getLinkIndex()], out);
2223  }
2224 }
2225 
2227 {
2228  std::stringstream ss;
2229  ss << "ROBOT: " << robot_model_->getName() << '\n';
2230  getStateTreeJointString(ss, robot_model_->getRootJoint(), " ", true);
2231  return ss.str();
2232 }
2233 
2234 namespace
2235 {
2236 void getPoseString(std::ostream& ss, const Eigen::Isometry3d& pose, const std::string& pfx)
2237 {
2238  ss.precision(3);
2239  for (int y = 0; y < 4; ++y)
2240  {
2241  ss << pfx;
2242  for (int x = 0; x < 4; ++x)
2243  {
2244  ss << std::setw(8) << pose(y, x) << " ";
2245  }
2246  ss << '\n';
2247  }
2248 }
2249 } // namespace
2250 
2251 void RobotState::getStateTreeJointString(std::ostream& ss, const JointModel* jm, const std::string& pfx0,
2252  bool last) const
2253 {
2254  std::string pfx = pfx0 + "+--";
2255 
2256  ss << pfx << "Joint: " << jm->getName() << '\n';
2257 
2258  pfx = pfx0 + (last ? " " : "| ");
2259 
2260  for (std::size_t i = 0; i < jm->getVariableCount(); ++i)
2261  {
2262  ss.precision(3);
2263  ss << pfx << jm->getVariableNames()[i] << std::setw(12) << position_[jm->getFirstVariableIndex() + i] << '\n';
2264  }
2265 
2266  const LinkModel* link_model = jm->getChildLinkModel();
2267 
2268  ss << pfx << "Link: " << link_model->getName() << '\n';
2269  getPoseString(ss, link_model->getJointOriginTransform(), pfx + "joint_origin:");
2270  if (variable_joint_transforms_)
2271  {
2272  getPoseString(ss, variable_joint_transforms_[jm->getJointIndex()], pfx + "joint_variable:");
2273  getPoseString(ss, global_link_transforms_[link_model->getLinkIndex()], pfx + "link_global:");
2274  }
2275 
2276  for (std::vector<const JointModel*>::const_iterator it = link_model->getChildJointModels().begin();
2277  it != link_model->getChildJointModels().end(); ++it)
2278  getStateTreeJointString(ss, *it, pfx, it + 1 == link_model->getChildJointModels().end());
2279 }
2280 
2281 std::ostream& operator<<(std::ostream& out, const RobotState& s)
2282 {
2283  s.printStateInfo(out);
2284  return out;
2285 }
2286 
2287 } // end of namespace core
2288 } // end of namespace moveit
Provides an interface for kinematics solvers.
std::function< double(const geometry_msgs::msg::Pose &, const moveit::core::RobotState &, moveit::core::JointModelGroup const *, const std::vector< double > &)> IKCostFn
Signature for a cost function used to evaluate IK solutions.
std::function< void(const geometry_msgs::msg::Pose &, const std::vector< double > &, moveit_msgs::msg::MoveItErrorCodes &)> IKCallbackFn
Signature for a callback to validate an IK solution. Typically used for collision checking.
This may be thrown if unrecoverable errors occur.
Definition: exceptions.h:53
Represents an axis-aligned bounding box.
Definition: aabb.h:47
void extendWithTransformedBox(const Eigen::Isometry3d &transform, const Eigen::Vector3d &box)
Extend with a box transformed by the given transform.
Definition: aabb.cpp:40
Object defining bodies that can be attached to robot links.
Definition: attached_body.h:58
const std::string & getAttachedLinkName() const
Get the name of the link this body is attached to.
Definition: attached_body.h:92
const Eigen::Isometry3d & getPose() const
Get the pose of the attached body relative to the parent link.
Definition: attached_body.h:80
static Distance computeCartesianPath(RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &traj, const LinkModel *link, const Eigen::Vector3d &translation, bool global_reference_frame, const MaxEEFStep &max_step, const JumpThreshold &jump_threshold, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
Compute the sequence of joint values that correspond to a straight Cartesian path for a particular li...
double getDefaultIKTimeout() const
Get the default IK timeout.
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
const std::string & getName() const
Get the name of the joint group.
const kinematics::KinematicsBaseConstPtr getSolverInstance() const
void getSubgroups(std::vector< const JointModelGroup * > &sub_groups) const
Get the groups that are subsets of this one (in terms of joints set)
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...
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
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
size_t getJointIndex() const
Get the index of this joint within the robot model.
Definition: joint_model.h:222
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
Definition: joint_model.h:131
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
virtual void computeTransform(const double *joint_values, Eigen::Isometry3d &transf) const =0
Given the joint values for a joint, compute the corresponding transform. The computed transform is gu...
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
int getFirstCollisionBodyTransformIndex() const
Definition: link_model.h:97
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
const Eigen::Isometry3d & getVisualMeshOrigin() const
Get the transform for the visual mesh origin.
Definition: link_model.h:224
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get shape associated to the collision geometry for this link.
Definition: link_model.h:176
const Eigen::Vector3d & getVisualMeshScale() const
Get the scale of the mesh resource for this link.
Definition: link_model.h:218
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 std::string & getName() const
The name of this link.
Definition: link_model.h:86
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
size_t getLinkIndex() const
The index of this joint when traversing the kinematic tree in depth first fashion.
Definition: link_model.h:92
const std::string & getVisualMeshFilename() const
Get the filename of the mesh resource used for visual display of this link.
Definition: link_model.h:212
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in this state....
void zeroVelocities()
Set all velocities to 0.0.
RobotState & operator=(const RobotState &other)
Copy operator.
void setJointEfforts(const JointModel *joint, const double *effort)
void setAttachedBodyUpdateCallback(const AttachedBodyCallback &callback)
void printTransforms(std::ostream &out=std::cout) const
void printTransform(const Eigen::Isometry3d &transform, std::ostream &out=std::cout) const
const LinkModel * getLinkModel(const std::string &link) const
Get the model of a particular link.
Definition: robot_state.h:122
void attachBody(std::unique_ptr< AttachedBody > attached_body)
Add an attached body to this state.
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
Definition: robot_state.h:1339
void updateStateWithLinkAt(const std::string &link_name, const Eigen::Isometry3d &transform, bool backward=false)
Update the state after setting a particular link to the input global transform pose.
Definition: robot_state.h:1314
bool getJacobian(const JointModelGroup *group, const LinkModel *link, const Eigen::Vector3d &reference_point_position, Eigen::MatrixXd &jacobian, bool use_quaternion_representation=false) const
Compute the Jacobian with reference to a particular point on a given link, for a specified group.
const double * getJointPositions(const std::string &joint_name) const
Definition: robot_state.h:557
std::pair< double, const JointModel * > getMinDistanceToPositionBounds() const
Get the minimm distance from this state to the bounds. The minimum distance and the joint for which t...
void copyJointGroupVelocities(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the velocity values of the variables that make up the group into another loca...
Definition: robot_state.h:791
void getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
const Eigen::Isometry3d & getJointTransform(const std::string &joint_name)
Definition: robot_state.h:1401
void setJointGroupAccelerations(const std::string &joint_group_name, const double *gstate)
Given accelerations for the variables that make up a group, in the order found in the group (includin...
Definition: robot_state.h:848
void setJointGroupVelocities(const std::string &joint_group_name, const double *gstate)
Given velocities for the variables that make up a group, in the order found in the group (including v...
Definition: robot_state.h:748
void computeVariableVelocity(const JointModelGroup *jmg, Eigen::VectorXd &qdot, const Eigen::VectorXd &twist, const LinkModel *tip) const
Given a twist for a particular link (tip), compute the corresponding velocity for every variable and ...
void computeAABB(std::vector< double > &aabb) const
Compute an axis-aligned bounding box that contains the current state. The format for aabb is (minx,...
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
Definition: robot_state.h:605
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
Definition: robot_state.h:691
bool clearAttachedBody(const std::string &id)
Remove the attached body named id. Return false if the object was not found (and thus not removed)....
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
Definition: robot_state.h:104
void harmonizePositions()
Call harmonizePosition() for all joints / all joints in group / given joint.
void setVariableVelocities(const double *velocity)
Given an array with velocity values for all variables, set those values as the velocities in this sta...
Definition: robot_state.h:253
bool dirtyCollisionBodyTransforms() const
Definition: robot_state.h:1439
void zeroAccelerations()
Set all accelerations to 0.0.
bool isValidVelocityMove(const RobotState &other, const JointModelGroup *group, double dt) const
Check that the time to move between two waypoints is sufficient given velocity limits and time step.
bool setFromDiffIK(const JointModelGroup *group, const Eigen::VectorXd &twist, const std::string &tip, double dt, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn())
Set the joint values from a Cartesian velocity applied during a time dt.
double * getVariablePositions()
Get a raw pointer to the positions of the variables stored in this state. Use carefully....
Definition: robot_state.h:147
void printStatePositionsWithJointLimits(const moveit::core::JointModelGroup *jmg, std::ostream &out=std::cout) const
Output to console the current state of the robot's joint limits.
void dropDynamics()
Reduce RobotState to kinematic information (remove velocity, acceleration and effort,...
bool dirtyJointTransform(const JointModel *joint) const
Definition: robot_state.h:1429
void setToRandomPositionsNearBy(const JointModelGroup *group, const RobotState &seed, double distance)
Set all joints in group to random values near the value in seed. distance is the maximum amount each ...
void updateLinkTransforms()
Update the reference frame transforms for links. This call is needed before using the transforms of l...
void interpolate(const RobotState &to, double t, RobotState &state) const
double distance(const RobotState &other) const
Return the sum of joint distances to "other" state. An L1 norm. Only considers active joints.
Definition: robot_state.h:1457
std::string getStateTreeString() const
const Eigen::Isometry3d & getFrameTransform(const std::string &frame_id, bool *frame_found=nullptr)
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
bool satisfiesBounds(double margin=0.0) const
void setVariableEffort(const double *effort)
Given an array with effort values for all variables, set those values as the effort in this state.
Definition: robot_state.h:445
void setJointGroupActivePositions(const JointModelGroup *group, const std::vector< double > &gstate)
Given positions for the variables of active joints that make up a group, in the order found in the gr...
bool dirtyLinkTransforms() const
Definition: robot_state.h:1434
void printStateInfo(std::ostream &out=std::cout) const
double getVariablePosition(const std::string &variable) const
Get the position of a particular variable. An exception is thrown if the variable is not known.
Definition: robot_state.h:207
void update(bool force=false)
Update all transforms.
void dropAccelerations()
Remove accelerations from this state (this differs from setting them to zero)
void getRobotMarkers(visualization_msgs::msg::MarkerArray &arr, const std::vector< std::string > &link_names, const std_msgs::msg::ColorRGBA &color, const std::string &ns, const rclcpp::Duration &dur, bool include_attached=false) const
Get a MarkerArray that fully describes the robot markers for a given robot.
const AttachedBody * getAttachedBody(const std::string &name) const
Get the attached body named name. Return nullptr if not found.
bool setFromIKSubgroups(const JointModelGroup *group, const EigenSTL::vector_Isometry3d &poses, const std::vector< std::string > &tips, const std::vector< std::vector< double >> &consistency_limits, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
setFromIK for multiple poses and tips (end effectors) when no solver exists for the jmg that can solv...
bool setToIKSolverFrame(Eigen::Isometry3d &pose, const kinematics::KinematicsBaseConstPtr &solver)
Transform pose from the robot model's base frame to the reference frame of the IK solver.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
void printStatePositions(std::ostream &out=std::cout) const
std::size_t getVariableCount() const
Get the number of variables that make up this state.
Definition: robot_state.h:110
void printDirtyInfo(std::ostream &out=std::cout) const
void setVariableAccelerations(const double *acceleration)
Given an array with acceleration values for all variables, set those values as the accelerations in t...
Definition: robot_state.h:348
void copyJointGroupAccelerations(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the acceleration values of the variables that make up the group into another ...
Definition: robot_state.h:891
RobotState(const RobotModelConstPtr &robot_model)
A state can be constructed from a specified robot model. No values are initialized....
Definition: robot_state.cpp:60
double computeCartesianPath(const JointModelGroup *group, std::vector< RobotStatePtr > &traj, const LinkModel *link, const Eigen::Vector3d &direction, bool global_reference_frame, double distance, double max_step, double jump_threshold_factor, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
Compute the sequence of joint values that correspond to a straight Cartesian path for a particular gr...
void dropEffort()
Remove effort values from this state (this differs from setting them to zero)
bool knowsFrameTransform(const std::string &frame_id) const
Check if a transformation matrix from the model frame (root of model) to frame frame_id is known.
bool integrateVariableVelocity(const JointModelGroup *jmg, const Eigen::VectorXd &qdot, double dt, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn())
Given the velocities for the variables in this group (qdot) and an amount of time (dt),...
bool hasAttachedBody(const std::string &id) const
Check if an attached body named id exists in this state.
random_numbers::RandomNumberGenerator & getRandomNumberGenerator()
Return the instance of a random number generator.
Definition: robot_state.h:1711
void invertVelocity()
Invert velocity if present.
const Eigen::Isometry3d & getFrameInfo(const std::string &frame_id, const LinkModel *&robot_link, bool &frame_found) const
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
void harmonizePosition(const JointModel *joint)
Definition: robot_state.h:1530
void clearAttachedBodies()
Clear all attached bodies. This calls delete on the AttachedBody instances, if needed.
void dropVelocities()
Remove velocities from this state (this differs from setting them to zero)
void zeroEffort()
Set all effort values to 0.0.
const moveit::core::LinkModel * getRigidlyConnectedParentLinkModel(const std::string &frame) const
Get the latest link upwards the kinematic tree which is only connected via fixed joints.
void updateCollisionBodyTransforms()
Update the transforms for the collision bodies. This call is needed before calling collision checking...
bool setFromIK(const JointModelGroup *group, const geometry_msgs::msg::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
If the group this state corresponds to is a chain and a solver is available, then the joint values ca...
void setJointPositions(const std::string &joint_name, const double *position)
Definition: robot_state.h:515
static bool sameFrame(const std::string &frame1, const std::string &frame2)
Check if two frames end up being the same once the missing / are added as prefix (if they are missing...
Definition: transforms.cpp:64
#define MOVEIT_CONSOLE_COLOR_RESET
#define MOVEIT_CONSOLE_COLOR_RED
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
std::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_...
Definition: robot_state.h:70
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::ostream & operator<<(std::ostream &out, const VariableBounds &b)
Operator overload for printing variable bounds to a stream.
std::map< std::string, Eigen::Isometry3d, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, Eigen::Isometry3d > > > FixedTransformsMap
Map frame names to the transformation matrix that can transform objects from the frame name to the pl...
Definition: transforms.h:53
std::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
Definition: attached_body.h:51
Main namespace for MoveIt.
Definition: exceptions.h:43
frame_id
Definition: pick.py:63
w
Definition: pick.py:67
x
Definition: pick.py:64
y
Definition: pick.py:65
z
Definition: pick.py:66
r
Definition: plan.py:56
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:55
d
Definition: setup.py:4
name
Definition: setup.py:7
Definition: world.h:49
A set of options for the kinematics solver.
Struct for containing jump_threshold.
Struct for containing max_step for computeCartesianPath.