moveit2
The MoveIt Motion Planning Framework for ROS 2.
default_constraint_samplers.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
38 #include <rclcpp/logger.hpp>
39 #include <rclcpp/logging.hpp>
40 #include <cassert>
41 #include <functional>
42 
43 namespace constraint_samplers
44 {
45 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_constraint_samplers.default_constraint_samplers");
46 
47 bool JointConstraintSampler::configure(const moveit_msgs::msg::Constraints& constr)
48 {
49  // construct the constraints
50  std::vector<kinematic_constraints::JointConstraint> jc;
51  for (const moveit_msgs::msg::JointConstraint& joint_constraint : constr.joint_constraints)
52  {
54  if (j.configure(joint_constraint))
55  jc.push_back(j);
56  }
57 
58  return jc.empty() ? false : configure(jc);
59 }
60 
61 bool JointConstraintSampler::configure(const std::vector<kinematic_constraints::JointConstraint>& jc)
62 {
63  clear();
64 
65  if (!jmg_)
66  {
67  RCLCPP_ERROR(LOGGER, "nullptr group specified for constraint sampler");
68  return false;
69  }
70 
71  // find and keep the constraints that operate on the group we sample
72  // also keep bounds for joints as convenient
73  std::map<std::string, JointInfo> bound_data;
74  bool some_valid_constraint = false;
75  for (const kinematic_constraints::JointConstraint& joint_constraint : jc)
76  {
77  if (!joint_constraint.enabled())
78  continue;
79 
80  const moveit::core::JointModel* jm = joint_constraint.getJointModel();
81  if (!jmg_->hasJointModel(jm->getName()))
82  continue;
83 
84  some_valid_constraint = true;
85 
86  const moveit::core::VariableBounds& joint_bounds = jm->getVariableBounds(joint_constraint.getJointVariableName());
87  JointInfo ji;
88  std::map<std::string, JointInfo>::iterator it = bound_data.find(joint_constraint.getJointVariableName());
89  if (it != bound_data.end())
90  ji = it->second;
91  else
92  ji.index_ = jmg_->getVariableGroupIndex(joint_constraint.getJointVariableName());
94  std::max(joint_bounds.min_position_,
95  joint_constraint.getDesiredJointPosition() - joint_constraint.getJointToleranceBelow()),
96  std::min(joint_bounds.max_position_,
97  joint_constraint.getDesiredJointPosition() + joint_constraint.getJointToleranceAbove()));
98 
99  RCLCPP_DEBUG(LOGGER, "Bounds for %s JointConstraint are %g %g", joint_constraint.getJointVariableName().c_str(),
100  ji.min_bound_, ji.max_bound_);
101 
102  if (ji.min_bound_ > ji.max_bound_ + std::numeric_limits<double>::epsilon())
103  {
104  std::stringstream cs;
105  joint_constraint.print(cs);
106  RCLCPP_ERROR(LOGGER,
107  "The constraints for joint '%s' are such that "
108  "there are no possible values for the joint: min_bound: %g, max_bound: %g. Failing.\n",
109  jm->getName().c_str(), ji.min_bound_, ji.max_bound_);
110  clear();
111  return false;
112  }
113  bound_data[joint_constraint.getJointVariableName()] = ji;
114  }
115 
116  if (!some_valid_constraint)
117  {
118  RCLCPP_WARN(LOGGER, "No valid joint constraints");
119  return false;
120  }
121 
122  for (std::pair<const std::string, JointInfo>& it : bound_data)
123  bounds_.push_back(it.second);
124 
125  // get a separate list of joints that are not bounded; we will sample these randomly
126  const std::vector<const moveit::core::JointModel*>& joints = jmg_->getJointModels();
127  for (const moveit::core::JointModel* joint : joints)
128  if (bound_data.find(joint->getName()) == bound_data.end() && joint->getVariableCount() > 0 &&
129  joint->getMimic() == nullptr)
130  {
131  // check if all the vars of the joint are found in bound_data instead
132  const std::vector<std::string>& vars = joint->getVariableNames();
133  if (vars.size() > 1)
134  {
135  bool all_found = true;
136  for (const std::string& var : vars)
137  if (bound_data.find(var) == bound_data.end())
138  {
139  all_found = false;
140  break;
141  }
142  if (all_found)
143  continue;
144  }
145  unbounded_.push_back(joint);
146  // Get the first variable name of this joint and find its index position in the planning group
147  uindex_.push_back(jmg_->getVariableGroupIndex(vars[0]));
148  }
149  values_.resize(jmg_->getVariableCount());
150  is_valid_ = true;
151  return true;
152 }
153 
155  const moveit::core::RobotState& /* reference_state */,
156  unsigned int /* max_attempts */)
157 {
158  if (!is_valid_)
159  {
160  RCLCPP_WARN(LOGGER, "JointConstraintSampler not configured, won't sample");
161  return false;
162  }
163 
164  // sample the unbounded joints first (in case some joint variables are bounded)
165  std::vector<double> v;
166  for (std::size_t i = 0; i < unbounded_.size(); ++i)
167  {
168  v.resize(unbounded_[i]->getVariableCount());
169  unbounded_[i]->getVariableRandomPositions(random_number_generator_, &v[0]);
170  for (std::size_t j = 0; j < v.size(); ++j)
171  values_[uindex_[i] + j] = v[j];
172  }
173 
174  // enforce the constraints for the constrained components (could be all of them)
175  for (const JointInfo& bound : bounds_)
176  values_[bound.index_] = random_number_generator_.uniformReal(bound.min_bound_, bound.max_bound_);
177 
179 
180  // we are always successful
181  return true;
182 }
183 
184 bool JointConstraintSampler::project(moveit::core::RobotState& state, unsigned int max_attempts)
185 {
186  return sample(state, state, max_attempts);
187 }
188 
190 {
192  bounds_.clear();
193  unbounded_.clear();
194  uindex_.clear();
195  values_.clear();
196 }
197 
199 {
200 }
201 
203  : position_constraint_(std::make_shared<kinematic_constraints::PositionConstraint>(pc))
204 {
205 }
206 
208  : orientation_constraint_(std::make_shared<kinematic_constraints::OrientationConstraint>(oc))
209 {
210 }
211 
214  : position_constraint_(std::make_shared<kinematic_constraints::PositionConstraint>(pc))
215  , orientation_constraint_(std::make_shared<kinematic_constraints::OrientationConstraint>(oc))
216 {
217 }
218 
219 IKSamplingPose::IKSamplingPose(const kinematic_constraints::PositionConstraintPtr& pc) : position_constraint_(pc)
220 {
221 }
222 
223 IKSamplingPose::IKSamplingPose(const kinematic_constraints::OrientationConstraintPtr& oc) : orientation_constraint_(oc)
224 {
225 }
226 
227 IKSamplingPose::IKSamplingPose(const kinematic_constraints::PositionConstraintPtr& pc,
228  const kinematic_constraints::OrientationConstraintPtr& oc)
229  : position_constraint_(pc), orientation_constraint_(oc)
230 {
231 }
232 
234 {
236  kb_.reset();
237  ik_frame_ = "";
238  transform_ik_ = false;
239  eef_to_ik_tip_transform_ = Eigen::Isometry3d::Identity();
241 }
242 
244 {
245  clear();
247  return false;
248  if ((!sp.orientation_constraint_ && !sp.position_constraint_->enabled()) ||
249  (!sp.position_constraint_ && !sp.orientation_constraint_->enabled()) ||
251  !sp.orientation_constraint_->enabled()))
252  {
253  RCLCPP_WARN(LOGGER, "No enabled constraints in sampling pose");
254  return false;
255  }
256 
257  sampling_pose_ = sp;
260  if (sampling_pose_.position_constraint_->getLinkModel()->getName() !=
261  sampling_pose_.orientation_constraint_->getLinkModel()->getName())
262  {
263  RCLCPP_ERROR(LOGGER, "Position and orientation constraints need to be specified for the same link "
264  "in order to use IK-based sampling");
265  return false;
266  }
267 
269  frame_depends_.push_back(sampling_pose_.position_constraint_->getReferenceFrame());
271  frame_depends_.push_back(sampling_pose_.orientation_constraint_->getReferenceFrame());
273  if (!kb_)
274  {
275  RCLCPP_WARN(LOGGER, "No solver instance in setup");
276  is_valid_ = false;
277  return false;
278  }
280  return is_valid_;
281 }
282 
283 bool IKConstraintSampler::configure(const moveit_msgs::msg::Constraints& constr)
284 {
285  for (std::size_t p = 0; p < constr.position_constraints.size(); ++p)
286  for (std::size_t o = 0; o < constr.orientation_constraints.size(); ++o)
287  if (constr.position_constraints[p].link_name == constr.orientation_constraints[o].link_name)
288  {
289  kinematic_constraints::PositionConstraintPtr pc(
290  new kinematic_constraints::PositionConstraint(scene_->getRobotModel()));
291  kinematic_constraints::OrientationConstraintPtr oc(
293  if (pc->configure(constr.position_constraints[p], scene_->getTransforms()) &&
294  oc->configure(constr.orientation_constraints[o], scene_->getTransforms()))
295  return configure(IKSamplingPose(pc, oc));
296  }
297 
298  for (const moveit_msgs::msg::PositionConstraint& position_constraint : constr.position_constraints)
299  {
300  kinematic_constraints::PositionConstraintPtr pc(
301  new kinematic_constraints::PositionConstraint(scene_->getRobotModel()));
302  if (pc->configure(position_constraint, scene_->getTransforms()))
303  return configure(IKSamplingPose(pc));
304  }
305 
306  for (const moveit_msgs::msg::OrientationConstraint& orientation_constraint : constr.orientation_constraints)
307  {
308  kinematic_constraints::OrientationConstraintPtr oc(
310  if (oc->configure(orientation_constraint, scene_->getTransforms()))
311  return configure(IKSamplingPose(oc));
312  }
313  return false;
314 }
315 
317 {
318  double v = 1.0;
320  {
321  const std::vector<bodies::BodyPtr>& constraint_regions =
322  sampling_pose_.position_constraint_->getConstraintRegions();
323  double vol = 0;
324  for (const bodies::BodyPtr& constraint_region : constraint_regions)
325  vol += constraint_region->computeVolume();
326  if (!constraint_regions.empty())
327  v *= vol;
328  }
329 
331  v *= sampling_pose_.orientation_constraint_->getXAxisTolerance() *
332  sampling_pose_.orientation_constraint_->getYAxisTolerance() *
333  sampling_pose_.orientation_constraint_->getZAxisTolerance();
334  return v;
335 }
336 
337 const std::string& IKConstraintSampler::getLinkName() const
338 {
340  return sampling_pose_.orientation_constraint_->getLinkModel()->getName();
341  return sampling_pose_.position_constraint_->getLinkModel()->getName();
342 }
343 
345 {
346  if (!kb_)
347  {
348  RCLCPP_ERROR(LOGGER, "No IK solver");
349  return false;
350  }
351 
352  // check if we need to transform the request into the coordinate frame expected by IK
353  ik_frame_ = kb_->getBaseFrame();
355  if (!ik_frame_.empty() && ik_frame_[0] == '/')
356  ik_frame_.erase(ik_frame_.begin());
357  if (transform_ik_)
359  {
360  RCLCPP_ERROR(LOGGER,
361  "The IK solver expects requests in frame '%s' but this frame is not known to the sampler. "
362  "Ignoring transformation (IK may fail)",
363  ik_frame_.c_str());
364  transform_ik_ = false;
365  }
366 
367  // check if IK is performed for the desired link
368  bool wrong_link = false;
370  {
371  const moveit::core::LinkModel* lm = sampling_pose_.position_constraint_->getLinkModel();
372  if (!moveit::core::Transforms::sameFrame(kb_->getTipFrame(), lm->getName()))
373  {
374  wrong_link = true;
376  for (const std::pair<const moveit::core::LinkModel* const, Eigen::Isometry3d>& fixed_link : fixed_links)
377  if (moveit::core::Transforms::sameFrame(fixed_link.first->getName(), kb_->getTipFrame()))
378  {
379  eef_to_ik_tip_transform_ = fixed_link.second; // valid isometry by contract
381  wrong_link = false;
382  break;
383  }
384  }
385  }
386 
387  if (!wrong_link && sampling_pose_.orientation_constraint_)
388  {
390  if (!moveit::core::Transforms::sameFrame(kb_->getTipFrame(), lm->getName()))
391  {
392  wrong_link = true;
394  for (const std::pair<const moveit::core::LinkModel* const, Eigen::Isometry3d>& fixed_link : fixed_links)
395  if (moveit::core::Transforms::sameFrame(fixed_link.first->getName(), kb_->getTipFrame()))
396  {
397  eef_to_ik_tip_transform_ = fixed_link.second; // valid isometry by contract
399  wrong_link = false;
400  break;
401  }
402  }
403  }
404 
405  if (wrong_link)
406  {
407  RCLCPP_ERROR(LOGGER, "IK cannot be performed for link '%s'. The solver can report IK solutions for link '%s'.",
409  sampling_pose_.position_constraint_->getLinkModel()->getName().c_str() :
410  sampling_pose_.orientation_constraint_->getLinkModel()->getName().c_str(),
411  kb_->getTipFrame().c_str());
412  return false;
413  }
414  return true;
415 }
416 
417 bool IKConstraintSampler::samplePose(Eigen::Vector3d& pos, Eigen::Quaterniond& quat, const moveit::core::RobotState& ks,
418  unsigned int max_attempts)
419 {
420  if (ks.dirtyLinkTransforms())
421  {
422  // samplePose below requires accurate transforms
423  RCLCPP_ERROR(LOGGER, "IKConstraintSampler received dirty robot state, but valid transforms are required. "
424  "Failing.");
425  return false;
426  }
427 
429  {
430  const std::vector<bodies::BodyPtr>& b = sampling_pose_.position_constraint_->getConstraintRegions();
431  if (!b.empty())
432  {
433  bool found = false;
434  std::size_t k = random_number_generator_.uniformInteger(0, b.size() - 1);
435  for (std::size_t i = 0; i < b.size(); ++i)
436  if (b[(i + k) % b.size()]->samplePointInside(random_number_generator_, max_attempts, pos))
437  {
438  found = true;
439  break;
440  }
441  if (!found)
442  {
443  RCLCPP_ERROR(LOGGER, "Unable to sample a point inside the constraint region");
444  return false;
445  }
446  }
447  else
448  {
449  RCLCPP_ERROR(LOGGER, "Unable to sample a point inside the constraint region. "
450  "Constraint region is empty when it should not be.");
451  return false;
452  }
453 
454  // if this constraint is with respect a mobile frame, we need to convert this rotation to the root frame of the
455  // model
456  if (sampling_pose_.position_constraint_->mobileReferenceFrame())
457  pos = ks.getFrameTransform(sampling_pose_.position_constraint_->getReferenceFrame()) * pos;
458  }
459  else
460  {
461  // do FK for rand state
462  moveit::core::RobotState temp_state(ks);
463  temp_state.setToRandomPositions(jmg_);
464  pos = temp_state.getGlobalLinkTransform(sampling_pose_.orientation_constraint_->getLinkModel()).translation();
465  }
466 
468  {
469  // sample a rotation matrix within the allowed bounds
470  double angle_x =
471  2.0 * (random_number_generator_.uniform01() - 0.5) *
472  (sampling_pose_.orientation_constraint_->getXAxisTolerance() - std::numeric_limits<double>::epsilon());
473  double angle_y =
474  2.0 * (random_number_generator_.uniform01() - 0.5) *
475  (sampling_pose_.orientation_constraint_->getYAxisTolerance() - std::numeric_limits<double>::epsilon());
476  double angle_z =
477  2.0 * (random_number_generator_.uniform01() - 0.5) *
478  (sampling_pose_.orientation_constraint_->getZAxisTolerance() - std::numeric_limits<double>::epsilon());
479 
480  Eigen::Isometry3d diff;
481  if (sampling_pose_.orientation_constraint_->getParameterizationType() ==
482  moveit_msgs::msg::OrientationConstraint::XYZ_EULER_ANGLES)
483  {
484  diff = Eigen::Isometry3d(Eigen::AngleAxisd(angle_x, Eigen::Vector3d::UnitX()) *
485  Eigen::AngleAxisd(angle_y, Eigen::Vector3d::UnitY()) *
486  Eigen::AngleAxisd(angle_z, Eigen::Vector3d::UnitZ()));
487  }
488  else if (sampling_pose_.orientation_constraint_->getParameterizationType() ==
489  moveit_msgs::msg::OrientationConstraint::ROTATION_VECTOR)
490  {
491  Eigen::Vector3d rotation_vector(angle_x, angle_y, angle_z);
492  diff = Eigen::Isometry3d(Eigen::AngleAxisd(rotation_vector.norm(), rotation_vector.normalized()));
493  }
494  else
495  {
496  /* The parameterization type should be validated in configure, so this should never happen. */
497  RCLCPP_ERROR(LOGGER, "The parameterization type for the orientation constraints is invalid.");
498  }
499  // diff is isometry by construction
500  // getDesiredRotationMatrix() returns a valid rotation matrix by contract
501  // reqr has thus to be a valid isometry
502  Eigen::Isometry3d reqr(sampling_pose_.orientation_constraint_->getDesiredRotationMatrix() * diff.linear());
503  quat = Eigen::Quaterniond(reqr.linear()); // reqr is isometry, so quat has to be normalized
504 
505  // if this constraint is with respect a mobile frame, we need to convert this rotation to the root frame of the
506  // model
507  if (sampling_pose_.orientation_constraint_->mobileReferenceFrame())
508  {
509  // getFrameTransform() returns a valid isometry by contract
510  const Eigen::Isometry3d& t = ks.getFrameTransform(sampling_pose_.orientation_constraint_->getReferenceFrame());
511  // rt is isometry by construction
512  Eigen::Isometry3d rt(t.linear() * quat);
513  quat = Eigen::Quaterniond(rt.linear()); // rt is isometry, so quat has to be normalized
514  }
515  }
516  else
517  {
518  // sample a random orientation
519  double q[4];
520  random_number_generator_.quaternion(q);
521  quat = Eigen::Quaterniond(q[3], q[0], q[1], q[2]); // quat is normalized by contract
522  }
523 
524  // if there is an offset, we need to undo the induced rotation in the sampled transform origin (point)
526  // the rotation matrix that corresponds to the desired orientation
527  pos = pos - quat * sampling_pose_.position_constraint_->getLinkOffset();
528 
529  return true;
530 }
531 
532 namespace
533 {
534 void samplingIkCallbackFnAdapter(moveit::core::RobotState* state, const moveit::core::JointModelGroup* jmg,
536  const std::vector<double>& ik_sol, moveit_msgs::msg::MoveItErrorCodes& error_code)
537 {
538  const std::vector<size_t>& bij = jmg->getKinematicsSolverJointBijection();
539  std::vector<double> solution(bij.size());
540  for (std::size_t i = 0; i < bij.size(); ++i)
541  solution[i] = ik_sol[bij[i]];
542  if (constraint(state, jmg, &solution[0]))
543  error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
544  else
545  error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
546 }
547 } // namespace
548 
550  unsigned int max_attempts)
551 {
552  return sampleHelper(state, reference_state, max_attempts, false);
553 }
554 
556  unsigned int max_attempts, bool project)
557 {
558  if (!is_valid_)
559  {
560  RCLCPP_WARN(LOGGER, "IKConstraintSampler not configured, won't sample");
561  return false;
562  }
563 
564  kinematics::KinematicsBase::IKCallbackFn adapted_ik_validity_callback;
566  adapted_ik_validity_callback = [this, state_ptr = &state](const geometry_msgs::msg::Pose&,
567  const std::vector<double>& joints,
568  moveit_msgs::msg::MoveItErrorCodes& error_code) {
569  return samplingIkCallbackFnAdapter(state_ptr, jmg_, group_state_validity_callback_, joints, error_code);
570  };
571 
572  for (unsigned int a = 0; a < max_attempts; ++a)
573  {
574  // sample a point in the constraint region
575  Eigen::Vector3d point;
576  Eigen::Quaterniond quat; // quat is normalized by contract
577  if (!samplePose(point, quat, reference_state, max_attempts))
578  {
579  if (verbose_)
580  RCLCPP_INFO(LOGGER, "IK constraint sampler was unable to produce a pose to run IK for");
581  return false;
582  }
583 
584  // we now have the transform we wish to perform IK for, in the planning frame
585  if (transform_ik_)
586  {
587  // we need to convert this transform to the frame expected by the IK solver
588  // both the planning frame and the frame for the IK are assumed to be robot links
589  Eigen::Isometry3d ikq(Eigen::Translation3d(point) * quat); // valid isometry by construction
590  // getFrameTransform() returns a valid isometry by contract
591  ikq = reference_state.getFrameTransform(ik_frame_).inverse() * ikq; // valid isometry * valid isometry
592  point = ikq.translation();
593  quat = Eigen::Quaterniond(ikq.linear()); // ikq is isometry, so quat is normalized
594  }
595 
597  {
598  // After sampling the pose needs to be transformed to the ik chain tip
599  Eigen::Isometry3d ikq(Eigen::Translation3d(point) * quat); // valid isometry by construction
600  ikq = ikq * eef_to_ik_tip_transform_; // eef_to_ik_tip_transform_ is valid isometry (checked in loadIKSolver())
601  point = ikq.translation();
602  quat = Eigen::Quaterniond(ikq.linear()); // ikq is isometry, so quat is normalized
603  }
604 
605  geometry_msgs::msg::Pose ik_query;
606  ik_query.position.x = point.x();
607  ik_query.position.y = point.y();
608  ik_query.position.z = point.z();
609  ik_query.orientation.x = quat.x();
610  ik_query.orientation.y = quat.y();
611  ik_query.orientation.z = quat.z();
612  ik_query.orientation.w = quat.w();
613 
614  if (callIK(ik_query, adapted_ik_validity_callback, ik_timeout_, state, project && a == 0))
615  return true;
616  }
617  return false;
618 }
619 
620 bool IKConstraintSampler::project(moveit::core::RobotState& state, unsigned int max_attempts)
621 {
622  return sampleHelper(state, state, max_attempts, true);
623 }
624 
626 {
627  state.update();
629  sampling_pose_.orientation_constraint_->decide(state, verbose_).satisfied) &&
631  sampling_pose_.position_constraint_->decide(state, verbose_).satisfied);
632 }
633 
634 bool IKConstraintSampler::callIK(const geometry_msgs::msg::Pose& ik_query,
635  const kinematics::KinematicsBase::IKCallbackFn& adapted_ik_validity_callback,
636  double timeout, moveit::core::RobotState& state, bool use_as_seed)
637 {
638  const std::vector<size_t>& ik_joint_bijection = jmg_->getKinematicsSolverJointBijection();
639  std::vector<double> seed(ik_joint_bijection.size(), 0.0);
640  std::vector<double> vals;
641 
642  if (use_as_seed)
643  state.copyJointGroupPositions(jmg_, vals);
644  else
645  // sample a seed value
647 
648  assert(vals.size() == ik_joint_bijection.size());
649  for (std::size_t i = 0; i < ik_joint_bijection.size(); ++i)
650  seed[i] = vals[ik_joint_bijection[i]];
651 
652  std::vector<double> ik_sol;
653  moveit_msgs::msg::MoveItErrorCodes error;
654 
655  if (adapted_ik_validity_callback ?
656  kb_->searchPositionIK(ik_query, seed, timeout, ik_sol, adapted_ik_validity_callback, error) :
657  kb_->searchPositionIK(ik_query, seed, timeout, ik_sol, error))
658  {
659  assert(ik_sol.size() == ik_joint_bijection.size());
660  std::vector<double> solution(ik_joint_bijection.size());
661  for (std::size_t i = 0; i < ik_joint_bijection.size(); ++i)
662  solution[ik_joint_bijection[i]] = ik_sol[i];
663  state.setJointGroupPositions(jmg_, solution);
664 
665  return validate(state);
666  }
667  else
668  {
669  if (error.val != moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION &&
670  error.val != moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE &&
671  error.val != moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT)
672  {
673  RCLCPP_ERROR(LOGGER, "IK solver failed with error %d", error.val);
674  }
675  else if (verbose_)
676  {
677  RCLCPP_INFO(LOGGER, "IK failed");
678  }
679  }
680  return false;
681 }
682 
683 } // end of namespace constraint_samplers
bool is_valid_
Holds the value for validity.
std::vector< std::string > frame_depends_
Holds the set of frames that must exist in the reference state to allow samples to be drawn.
const moveit::core::JointModelGroup *const jmg_
Holds the joint model group associated with this constraint.
virtual void clear()
Clears all data from the constraint.
moveit::core::GroupStateValidityCallbackFn group_state_validity_callback_
Holds the callback for state validity.
bool verbose_
True if verbosity is on.
planning_scene::PlanningSceneConstPtr scene_
Holds the planning scene.
bool configure(const moveit_msgs::msg::Constraints &constr) override
Configures the IK constraint given a constraints message.
double ik_timeout_
Holds the timeout associated with IK.
bool loadIKSolver()
Performs checks and sets various internal values associated with the IK solver.
const std::string & getLinkName() const
Gets the link name associated with this sampler.
bool validate(moveit::core::RobotState &state) const
IKSamplingPose sampling_pose_
Holder for the pose used for sampling.
bool callIK(const geometry_msgs::msg::Pose &ik_query, const kinematics::KinematicsBase::IKCallbackFn &adapted_ik_validity_callback, double timeout, moveit::core::RobotState &state, bool use_as_seed)
Actually calls IK on the given pose, generating a random seed state.
double getSamplingVolume() const
Gets the volume associated with the position and orientation constraints.
Eigen::Isometry3d eef_to_ik_tip_transform_
Holds the transformation from end effector to IK tip frame.
bool need_eef_to_ik_tip_transform_
True if the tip frame of the inverse kinematic is different than the frame of the end effector.
kinematics::KinematicsBaseConstPtr kb_
Holds the kinematics solver.
void clear() override
Clears all data from the constraint.
std::string ik_frame_
Holds the base from of the IK solver.
random_numbers::RandomNumberGenerator random_number_generator_
Random generator used by the sampler.
bool project(moveit::core::RobotState &state, unsigned int max_attempts) override
Project a sample given the constraints, updating the joint state group. This function allows the para...
bool transform_ik_
True if the frame associated with the kinematic model is different than the base frame of the IK solv...
bool sample(moveit::core::RobotState &state, const moveit::core::RobotState &reference_state, unsigned int max_attempts) override
Produces an IK sample.
bool sampleHelper(moveit::core::RobotState &state, const moveit::core::RobotState &reference_state, unsigned int max_attempts, bool project)
bool samplePose(Eigen::Vector3d &pos, Eigen::Quaterniond &quat, const moveit::core::RobotState &ks, unsigned int max_attempts)
Returns a pose that falls within the constraint regions.
std::vector< unsigned int > uindex_
The index of the unbounded joints in the joint state vector.
bool project(moveit::core::RobotState &state, unsigned int max_attempts) override
Project a sample given the constraints, updating the joint state group. This function allows the para...
void clear() override
Clears all data from the constraint.
random_numbers::RandomNumberGenerator random_number_generator_
Random number generator used to sample.
std::vector< const moveit::core::JointModel * > unbounded_
The joints that are not bounded except by joint limits.
bool configure(const moveit_msgs::msg::Constraints &constr) override
Configures a joint constraint given a Constraints message.
std::vector< JointInfo > bounds_
The bounds for any joint with bounds that are more restrictive than the joint limits.
bool sample(moveit::core::RobotState &state, const moveit::core::RobotState &ks, unsigned int max_attempts) override
Samples given the constraints, populating state. This function allows the parameter max_attempts to b...
std::vector< double > values_
Values associated with this group to avoid continuously reallocating.
Class for handling single DOF joint constraints.
bool configure(const moveit_msgs::msg::JointConstraint &jc)
Configure the constraint based on a moveit_msgs::msg::JointConstraint.
Class for constraints on the orientation of a link.
Class for constraints on the XYZ position of a link.
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.
double getDefaultIKTimeout() const
Get the default IK timeout.
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values) const
Compute random values for the state of the joint group.
const std::vector< const JointModel * > & getJointModels() const
Get all the joints in this group (including fixed and mimic joints).
const kinematics::KinematicsBaseConstPtr getSolverInstance() const
bool hasJointModel(const std::string &joint) const
Check if a joint is part of this group.
const RobotModel & getParentModel() const
Get the kinematic model this group is part of.
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...
int getVariableGroupIndex(const std::string &variable) const
Get the index of a variable within the group. Return -1 on error.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
const std::string & getName() const
Get the name of the joint.
Definition: joint_model.h:145
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a variable. Throw an exception if the variable was not found.
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:72
const LinkTransformMap & getAssociatedFixedTransforms() const
Get the set of links that are attached to this one via fixed transforms. The returned transforms are ...
Definition: link_model.h:199
const std::string & getName() const
The name of this link.
Definition: link_model.h:86
const std::string & getModelFrame() const
Get the frame in which the transforms for this model are computed (when using a RobotState)....
Definition: robot_model.h:94
bool hasLinkModel(const std::string &name) const
Check if a link exists. Return true if it does.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
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 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
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 dirtyLinkTransforms() const
Definition: robot_state.h:1434
void update(bool force=false)
Update all transforms.
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
string project
Definition: conf.py:22
The constraint samplers namespace contains a number of methods for generating samples based on a cons...
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
Representation and evaluation of kinematic constraints.
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
p
Definition: pick.py:62
a
Definition: plan.py:54
A structure for potentially holding a position constraint and an orientation constraint for use durin...
kinematic_constraints::PositionConstraintPtr position_constraint_
Holds the position constraint for sampling.
kinematic_constraints::OrientationConstraintPtr orientation_constraint_
Holds the orientation constraint for sampling.
An internal structure used for maintaining constraints on a particular joint.
void potentiallyAdjustMinMaxBounds(double min, double max)
Function that adjusts the joints only if they are more restrictive. This means that the min limit is ...