moveit2
The MoveIt Motion Planning Framework for ROS 2.
kinematic_constraint.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 <geometric_shapes/body_operations.h>
39 #include <geometric_shapes/shape_operations.h>
42 #include <geometric_shapes/check_isometry.h>
43 #include <rclcpp/logger.hpp>
44 #include <rclcpp/logging.hpp>
45 #include <rclcpp/time.hpp>
46 #include <tf2_eigen/tf2_eigen.hpp>
47 #include <functional>
48 #include <limits>
49 #include <math.h>
50 #include <memory>
51 #include <typeinfo>
52 
53 #include <rclcpp/clock.hpp>
54 #include <rclcpp/duration.hpp>
55 
56 namespace kinematic_constraints
57 {
58 // Logger
59 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_kinematic_constraints.kinematic_constraints");
60 
61 static double normalizeAngle(double angle)
62 {
63  double v = fmod(angle, 2.0 * M_PI);
64  if (v < -M_PI)
65  v += 2.0 * M_PI;
66  else if (v > M_PI)
67  v -= 2.0 * M_PI;
68  return v;
69 }
70 
71 // Normalizes an angle to the interval [-pi, +pi] and then take the absolute value
72 // The returned values will be in the following range [0, +pi]
73 static double normalizeAbsoluteAngle(const double angle)
74 {
75  const double normalized_angle = std::fmod(std::abs(angle), 2 * M_PI);
76  return std::min(2 * M_PI - normalized_angle, normalized_angle);
77 }
78 
86 template <typename Derived>
87 std::tuple<Eigen::Matrix<typename Eigen::MatrixBase<Derived>::Scalar, 3, 1>, bool>
88 CalcEulerAngles(const Eigen::MatrixBase<Derived>& R)
89 {
90  using std::atan2;
91  using std::sqrt;
92  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Derived, 3, 3)
93  using Index = EIGEN_DEFAULT_DENSE_INDEX_TYPE;
94  using Scalar = typename Eigen::MatrixBase<Derived>::Scalar;
95  const Index i = 0;
96  const Index j = 1;
97  const Index k = 2;
98  Eigen::Matrix<Scalar, 3, 1> res;
99  const Scalar rsum = sqrt((R(i, i) * R(i, i) + R(i, j) * R(i, j) + R(j, k) * R(j, k) + R(k, k) * R(k, k)) / 2);
100  res[1] = atan2(R(i, k), rsum);
101  // There is a singularity when cos(beta) == 0
102  if (rsum > 4 * Eigen::NumTraits<Scalar>::epsilon())
103  { // cos(beta) != 0
104  res[0] = atan2(-R(j, k), R(k, k));
105  res[2] = atan2(-R(i, j), R(i, i));
106  return { res, true };
107  }
108  else if (R(i, k) > 0)
109  { // cos(beta) == 0 and sin(beta) == 1
110  const Scalar spos = R(j, i) + R(k, j); // 2*sin(alpha + gamma)
111  const Scalar cpos = R(j, j) - R(k, i); // 2*cos(alpha + gamma)
112  res[0] = atan2(spos, cpos);
113  res[2] = 0;
114  return { res, false };
115  } // cos(beta) == 0 and sin(beta) == -1
116  const Scalar sneg = R(k, j) - R(j, i); // 2*sin(alpha + gamma)
117  const Scalar cneg = R(j, j) + R(k, i); // 2*cos(alpha + gamma)
118  res[0] = atan2(sneg, cneg);
119  res[2] = 0;
120  return { res, false };
121 }
122 
123 KinematicConstraint::KinematicConstraint(const moveit::core::RobotModelConstPtr& model)
124  : type_(UNKNOWN_CONSTRAINT), robot_model_(model), constraint_weight_(std::numeric_limits<double>::epsilon())
125 {
126 }
127 
129 
130 bool JointConstraint::configure(const moveit_msgs::msg::JointConstraint& jc)
131 {
132  // clearing before we configure to get rid of any old data
133  clear();
134 
135  // testing tolerances first
136  if (jc.tolerance_above < 0.0 || jc.tolerance_below < 0.0)
137  {
138  RCLCPP_WARN(LOGGER, "JointConstraint tolerance values must be positive.");
139  joint_model_ = nullptr;
140  return false;
141  }
142 
143  joint_variable_name_ = jc.joint_name;
144  local_variable_name_.clear();
145  if (robot_model_->hasJointModel(joint_variable_name_))
147  else
148  {
149  std::size_t pos = jc.joint_name.find_last_of('/');
150  if (pos != std::string::npos)
151  {
152  joint_model_ = robot_model_->getJointModel(jc.joint_name.substr(0, pos));
153  if (pos + 1 < jc.joint_name.length())
154  local_variable_name_ = jc.joint_name.substr(pos + 1);
155  }
156  else
157  joint_model_ = robot_model_->getJointModel(jc.joint_name);
158  }
159 
160  if (joint_model_)
161  {
162  if (local_variable_name_.empty())
163  {
164  // check if the joint has 1 DOF (the only kind we can handle)
165  if (joint_model_->getVariableCount() == 0)
166  {
167  RCLCPP_ERROR(LOGGER, "Joint '%s' has no parameters to constrain", jc.joint_name.c_str());
168  joint_model_ = nullptr;
169  }
170  else if (joint_model_->getVariableCount() > 1)
171  {
172  RCLCPP_ERROR(LOGGER,
173  "Joint '%s' has more than one parameter to constrain. "
174  "This type of constraint is not supported.",
175  jc.joint_name.c_str());
176  joint_model_ = nullptr;
177  }
178  }
179  else
180  {
181  int found = -1;
182  const std::vector<std::string>& local_var_names = joint_model_->getLocalVariableNames();
183  for (std::size_t i = 0; i < local_var_names.size(); ++i)
184  if (local_var_names[i] == local_variable_name_)
185  {
186  found = i;
187  break;
188  }
189  if (found < 0)
190  {
191  RCLCPP_ERROR(LOGGER, "Local variable name '%s' is not known to joint '%s'", local_variable_name_.c_str(),
192  joint_model_->getName().c_str());
193  joint_model_ = nullptr;
194  }
195  }
196  }
197 
198  if (joint_model_)
199  {
200  joint_is_continuous_ = false;
201  joint_tolerance_above_ = jc.tolerance_above;
202  joint_tolerance_below_ = jc.tolerance_below;
204 
205  // check if we have to wrap angles when computing distances
206  joint_is_continuous_ = false;
208  {
209  const moveit::core::RevoluteJointModel* rjoint =
210  static_cast<const moveit::core::RevoluteJointModel*>(joint_model_);
211  if (rjoint->isContinuous())
212  joint_is_continuous_ = true;
213  }
215  {
216  if (local_variable_name_ == "theta")
217  joint_is_continuous_ = true;
218  }
219 
221  {
222  joint_position_ = normalizeAngle(jc.position);
223  }
224  else
225  {
226  joint_position_ = jc.position;
228 
230  {
232  joint_tolerance_above_ = std::numeric_limits<double>::epsilon();
233  RCLCPP_WARN(LOGGER,
234  "Joint %s is constrained to be below the minimum bounds. "
235  "Assuming minimum bounds instead.",
236  jc.joint_name.c_str());
237  }
239  {
241  joint_tolerance_below_ = std::numeric_limits<double>::epsilon();
242  RCLCPP_WARN(LOGGER,
243  "Joint %s is constrained to be above the maximum bounds. "
244  "Assuming maximum bounds instead.",
245  jc.joint_name.c_str());
246  }
247  }
248 
249  if (jc.weight <= std::numeric_limits<double>::epsilon())
250  {
251  RCLCPP_WARN(LOGGER, "The weight on constraint for joint '%s' is very near zero. Setting to 1.0.",
252  jc.joint_name.c_str());
253  constraint_weight_ = 1.0;
254  }
255  else
256  constraint_weight_ = jc.weight;
257  }
258  return joint_model_ != nullptr;
259 }
260 
261 bool JointConstraint::equal(const KinematicConstraint& other, double margin) const
262 {
263  if (other.getType() != type_)
264  return false;
265  const JointConstraint& o = static_cast<const JointConstraint&>(other);
267  return fabs(joint_position_ - o.joint_position_) <= margin &&
268  fabs(joint_tolerance_above_ - o.joint_tolerance_above_) <= margin &&
270  return false;
271 }
272 
274 {
275  if (!joint_model_)
276  return ConstraintEvaluationResult(true, 0.0);
277 
278  double current_joint_position = state.getVariablePosition(joint_variable_index_);
279  double dif = 0.0;
280 
281  // compute signed shortest distance for continuous joints
283  {
284  dif = normalizeAngle(current_joint_position) - joint_position_;
285 
286  if (dif > M_PI)
287  dif = 2.0 * M_PI - dif;
288  else if (dif < -M_PI)
289  dif += 2.0 * M_PI; // we include a sign change to have dif > 0
290  }
291  else
292  dif = current_joint_position - joint_position_;
293 
294  // check bounds
295  bool result = dif <= (joint_tolerance_above_ + 2.0 * std::numeric_limits<double>::epsilon()) &&
296  dif >= (-joint_tolerance_below_ - 2.0 * std::numeric_limits<double>::epsilon());
297  if (verbose)
298  RCLCPP_INFO(LOGGER,
299  "Constraint %s:: Joint name: '%s', actual value: %f, desired value: %f, "
300  "tolerance_above: %f, tolerance_below: %f",
301  result ? "satisfied" : "violated", joint_variable_name_.c_str(), current_joint_position,
303  return ConstraintEvaluationResult(result, constraint_weight_ * fabs(dif));
304 }
305 
307 {
308  return joint_model_;
309 }
310 
312 {
313  joint_model_ = nullptr;
315  joint_is_continuous_ = false;
319 }
320 
321 void JointConstraint::print(std::ostream& out) const
322 {
323  if (joint_model_)
324  {
325  out << "Joint constraint for joint " << joint_variable_name_ << ": \n";
326  out << " value = ";
327  out << joint_position_ << "; ";
328  out << " tolerance below = ";
329  out << joint_tolerance_below_ << "; ";
330  out << " tolerance above = ";
331  out << joint_tolerance_above_ << "; ";
332  out << '\n';
333  }
334  else
335  out << "No constraint" << '\n';
336 }
337 
338 bool PositionConstraint::configure(const moveit_msgs::msg::PositionConstraint& pc, const moveit::core::Transforms& tf)
339 {
340  // clearing before we configure to get rid of any old data
341  clear();
342 
343  link_model_ = robot_model_->getLinkModel(pc.link_name);
344  if (link_model_ == nullptr)
345  {
346  RCLCPP_WARN(LOGGER, "Position constraint link model %s not found in kinematic model. Constraint invalid.",
347  pc.link_name.c_str());
348  return false;
349  }
350 
351  if (pc.header.frame_id.empty())
352  {
353  RCLCPP_WARN(LOGGER, "No frame specified for position constraint on link '%s'!", pc.link_name.c_str());
354  return false;
355  }
356 
357  offset_ = Eigen::Vector3d(pc.target_point_offset.x, pc.target_point_offset.y, pc.target_point_offset.z);
358  has_offset_ = offset_.squaredNorm() > std::numeric_limits<double>::epsilon();
359 
360  if (tf.isFixedFrame(pc.header.frame_id))
361  {
363  mobile_frame_ = false;
364  }
365  else
366  {
367  constraint_frame_id_ = pc.header.frame_id;
368  mobile_frame_ = true;
369  }
370 
371  // load primitive shapes, first clearing any we already have
372  for (std::size_t i = 0; i < pc.constraint_region.primitives.size(); ++i)
373  {
374  std::unique_ptr<shapes::Shape> shape(shapes::constructShapeFromMsg(pc.constraint_region.primitives[i]));
375  if (shape)
376  {
377  if (pc.constraint_region.primitive_poses.size() <= i)
378  {
379  RCLCPP_WARN(LOGGER, "Constraint region message does not contain enough primitive poses");
380  continue;
381  }
382  Eigen::Isometry3d t;
383  tf2::fromMsg(pc.constraint_region.primitive_poses[i], t);
384  ASSERT_ISOMETRY(t) // unsanitized input, could contain a non-isometry
385  constraint_region_pose_.push_back(t);
386  if (!mobile_frame_)
387  tf.transformPose(pc.header.frame_id, constraint_region_pose_.back(), constraint_region_pose_.back());
388 
389  const bodies::BodyPtr body(bodies::createEmptyBodyFromShapeType(shape->type));
390  body->setDimensionsDirty(shape.get());
391  body->setPoseDirty(constraint_region_pose_.back());
392  body->updateInternalData();
393  constraint_region_.push_back(body);
394  }
395  else
396  RCLCPP_WARN(LOGGER, "Could not construct primitive shape %zu", i);
397  }
398 
399  // load meshes
400  for (std::size_t i = 0; i < pc.constraint_region.meshes.size(); ++i)
401  {
402  std::unique_ptr<shapes::Shape> shape(shapes::constructShapeFromMsg(pc.constraint_region.meshes[i]));
403  if (shape)
404  {
405  if (pc.constraint_region.mesh_poses.size() <= i)
406  {
407  RCLCPP_WARN(LOGGER, "Constraint region message does not contain enough primitive poses");
408  continue;
409  }
410  Eigen::Isometry3d t;
411  tf2::fromMsg(pc.constraint_region.mesh_poses[i], t);
412  ASSERT_ISOMETRY(t) // unsanitized input, could contain a non-isometry
413  constraint_region_pose_.push_back(t);
414  if (!mobile_frame_)
415  tf.transformPose(pc.header.frame_id, constraint_region_pose_.back(), constraint_region_pose_.back());
416  const bodies::BodyPtr body(bodies::createEmptyBodyFromShapeType(shape->type));
417  body->setDimensionsDirty(shape.get());
418  body->setPoseDirty(constraint_region_pose_.back());
419  body->updateInternalData();
420  constraint_region_.push_back(body);
421  }
422  else
423  {
424  RCLCPP_WARN(LOGGER, "Could not construct mesh shape %zu", i);
425  }
426  }
427 
428  if (pc.weight <= std::numeric_limits<double>::epsilon())
429  {
430  RCLCPP_WARN(LOGGER, "The weight on position constraint for link '%s' is near zero. Setting to 1.0.",
431  pc.link_name.c_str());
432  constraint_weight_ = 1.0;
433  }
434  else
435  constraint_weight_ = pc.weight;
436 
437  return !constraint_region_.empty();
438 }
439 
440 bool PositionConstraint::equal(const KinematicConstraint& other, double margin) const
441 {
442  if (other.getType() != type_)
443  return false;
444  const PositionConstraint& o = static_cast<const PositionConstraint&>(other);
445 
447  {
448  if ((offset_ - o.offset_).norm() > margin)
449  return false;
450  std::vector<bool> other_region_matches_this(constraint_region_.size(), false);
451  for (std::size_t i = 0; i < constraint_region_.size(); ++i)
452  {
453  bool some_match = false;
454  // need to check against all other regions
455  for (std::size_t j = 0; j < o.constraint_region_.size(); ++j)
456  {
457  // constraint_region_pose_ contain only valid isometries, so diff is also a valid isometry
458  Eigen::Isometry3d diff = constraint_region_pose_[i].inverse() * o.constraint_region_pose_[j];
459  if (diff.translation().norm() < margin && diff.linear().isIdentity(margin) &&
460  constraint_region_[i]->getType() == o.constraint_region_[j]->getType() &&
461  fabs(constraint_region_[i]->computeVolume() - o.constraint_region_[j]->computeVolume()) < margin)
462  {
463  some_match = true;
464  // can't break, as need to do matches the other way as well
465  other_region_matches_this[j] = true;
466  }
467  }
468  if (!some_match)
469  return false;
470  }
471  for (std::size_t i = 0; i < o.constraint_region_.size(); ++i)
472  if (!other_region_matches_this[i])
473  return false;
474  return true;
475  }
476  return false;
477 }
478 
479 // helper function to avoid code duplication
480 static inline ConstraintEvaluationResult finishPositionConstraintDecision(const Eigen::Vector3d& pt,
481  const Eigen::Vector3d& desired,
482  const std::string& name, double weight,
483  bool result, bool verbose)
484 {
485  double dx = desired.x() - pt.x();
486  double dy = desired.y() - pt.y();
487  double dz = desired.z() - pt.z();
488  if (verbose)
489  {
490  RCLCPP_INFO(LOGGER, "Position constraint %s on link '%s'. Desired: %f, %f, %f, current: %f, %f, %f",
491  result ? "satisfied" : "violated", name.c_str(), desired.x(), desired.y(), desired.z(), pt.x(), pt.y(),
492  pt.z());
493  RCLCPP_INFO(LOGGER, "Differences %g %g %g", dx, dy, dz);
494  }
495  return ConstraintEvaluationResult(result, weight * sqrt(dx * dx + dy * dy + dz * dz));
496 }
497 
499 {
500  if (!link_model_ || constraint_region_.empty())
501  return ConstraintEvaluationResult(true, 0.0);
502 
504  if (mobile_frame_)
505  {
506  for (std::size_t i = 0; i < constraint_region_.size(); ++i)
507  {
508  Eigen::Isometry3d tmp = state.getFrameTransform(constraint_frame_id_) * constraint_region_pose_[i];
509  bool result = constraint_region_[i]->cloneAt(tmp)->containsPoint(pt, verbose);
510  if (result || (i + 1 == constraint_region_pose_.size()))
511  return finishPositionConstraintDecision(pt, tmp.translation(), link_model_->getName(), constraint_weight_,
512  result, verbose);
513  else
514  finishPositionConstraintDecision(pt, tmp.translation(), link_model_->getName(), constraint_weight_, result,
515  verbose);
516  }
517  }
518  else
519  {
520  for (std::size_t i = 0; i < constraint_region_.size(); ++i)
521  {
522  bool result = constraint_region_[i]->containsPoint(pt, true);
523  if (result || (i + 1 == constraint_region_.size()))
524  return finishPositionConstraintDecision(pt, constraint_region_[i]->getPose().translation(),
525  link_model_->getName(), constraint_weight_, result, verbose);
526  else
527  finishPositionConstraintDecision(pt, constraint_region_[i]->getPose().translation(), link_model_->getName(),
528  constraint_weight_, result, verbose);
529  }
530  }
531  return ConstraintEvaluationResult(false, 0.0);
532 }
533 
534 void PositionConstraint::print(std::ostream& out) const
535 {
536  if (enabled())
537  out << "Position constraint on link '" << link_model_->getName() << "'" << '\n';
538  else
539  out << "No constraint" << '\n';
540 }
541 
543 {
544  offset_ = Eigen::Vector3d(0.0, 0.0, 0.0);
545  has_offset_ = false;
546  constraint_region_.clear();
547  constraint_region_pose_.clear();
548  mobile_frame_ = false;
550  link_model_ = nullptr;
551 }
552 
554 {
555  return link_model_ && !constraint_region_.empty();
556 }
557 
558 bool OrientationConstraint::configure(const moveit_msgs::msg::OrientationConstraint& oc,
559  const moveit::core::Transforms& tf)
560 {
561  // clearing out any old data
562  clear();
563 
564  link_model_ = robot_model_->getLinkModel(oc.link_name);
565  if (!link_model_)
566  {
567  RCLCPP_WARN(LOGGER, "Could not find link model for link name %s", oc.link_name.c_str());
568  return false;
569  }
570  Eigen::Quaterniond q;
571  tf2::fromMsg(oc.orientation, q);
572  if (fabs(q.norm() - 1.0) > 1e-3)
573  {
574  RCLCPP_WARN(LOGGER,
575  "Orientation constraint for link '%s' is probably incorrect: %f, %f, %f, "
576  "%f. Assuming identity instead.",
577  oc.link_name.c_str(), oc.orientation.x, oc.orientation.y, oc.orientation.z, oc.orientation.w);
578  q = Eigen::Quaterniond(1.0, 0.0, 0.0, 0.0);
579  }
580 
581  if (oc.header.frame_id.empty())
582  RCLCPP_WARN(LOGGER, "No frame specified for position constraint on link '%s'!", oc.link_name.c_str());
583 
584  if (tf.isFixedFrame(oc.header.frame_id))
585  {
586  tf.transformQuaternion(oc.header.frame_id, q, q);
588  desired_rotation_matrix_ = Eigen::Matrix3d(q);
590  mobile_frame_ = false;
591  }
592  else
593  {
594  desired_rotation_frame_id_ = oc.header.frame_id;
595  desired_rotation_matrix_ = Eigen::Matrix3d(q);
596  mobile_frame_ = true;
597  }
598  std::stringstream matrix_str;
599  matrix_str << desired_rotation_matrix_;
600  RCLCPP_DEBUG(LOGGER, "The desired rotation matrix for link '%s' in frame %s is:\n%s", oc.link_name.c_str(),
601  desired_rotation_frame_id_.c_str(), matrix_str.str().c_str());
602 
603  if (oc.weight <= std::numeric_limits<double>::epsilon())
604  {
605  RCLCPP_WARN(LOGGER, "The weight on orientation constraint for link '%s' is near zero. Setting to 1.0.",
606  oc.link_name.c_str());
607  constraint_weight_ = 1.0;
608  }
609  else
610  {
611  constraint_weight_ = oc.weight;
612  }
613 
614  parameterization_type_ = oc.parameterization;
615  // validate the parameterization, set to default value if invalid
616  if (parameterization_type_ != moveit_msgs::msg::OrientationConstraint::XYZ_EULER_ANGLES &&
617  parameterization_type_ != moveit_msgs::msg::OrientationConstraint::ROTATION_VECTOR)
618  {
619  RCLCPP_WARN(LOGGER,
620  "Unknown parameterization for orientation constraint tolerance, using default (XYZ_EULER_ANGLES).");
621  parameterization_type_ = moveit_msgs::msg::OrientationConstraint::XYZ_EULER_ANGLES;
622  }
623 
624  absolute_x_axis_tolerance_ = fabs(oc.absolute_x_axis_tolerance);
625  if (absolute_x_axis_tolerance_ < std::numeric_limits<double>::epsilon())
626  RCLCPP_WARN(LOGGER, "Near-zero value for absolute_x_axis_tolerance");
627  absolute_y_axis_tolerance_ = fabs(oc.absolute_y_axis_tolerance);
628  if (absolute_y_axis_tolerance_ < std::numeric_limits<double>::epsilon())
629  RCLCPP_WARN(LOGGER, "Near-zero value for absolute_y_axis_tolerance");
630  absolute_z_axis_tolerance_ = fabs(oc.absolute_z_axis_tolerance);
631  if (absolute_z_axis_tolerance_ < std::numeric_limits<double>::epsilon())
632  RCLCPP_WARN(LOGGER, "Near-zero value for absolute_z_axis_tolerance");
633 
634  return link_model_ != nullptr;
635 }
636 
637 bool OrientationConstraint::equal(const KinematicConstraint& other, double margin) const
638 {
639  if (other.getType() != type_)
640  return false;
641  const OrientationConstraint& o = static_cast<const OrientationConstraint&>(other);
642 
643  if (o.link_model_ == link_model_ &&
645  {
647  return false;
648  return fabs(absolute_x_axis_tolerance_ - o.absolute_x_axis_tolerance_) <= margin &&
651  }
652  return false;
653 }
654 
656 {
657  link_model_ = nullptr;
658  desired_rotation_matrix_ = Eigen::Matrix3d::Identity();
659  desired_rotation_matrix_inv_ = Eigen::Matrix3d::Identity();
661  mobile_frame_ = false;
663 }
664 
666 {
667  return link_model_;
668 }
669 
671 {
672  if (!link_model_)
673  return ConstraintEvaluationResult(true, 0.0);
674 
675  Eigen::Isometry3d diff;
676  if (mobile_frame_)
677  {
678  // getFrameTransform() returns a valid isometry by contract
679  Eigen::Matrix3d tmp = state.getFrameTransform(desired_rotation_frame_id_).linear() * desired_rotation_matrix_;
680  // getGlobalLinkTransform() returns a valid isometry by contract
681  diff = Eigen::Isometry3d(tmp.transpose() * state.getGlobalLinkTransform(link_model_).linear()); // valid isometry
682  }
683  else
684  {
685  // diff is valid isometry by construction
686  diff = Eigen::Isometry3d(desired_rotation_matrix_inv_ * state.getGlobalLinkTransform(link_model_).linear());
687  }
688 
689  // This needs to live outside the if-block scope (as xyz_rotation points to its data).
690  std::tuple<Eigen::Vector3d, bool> euler_angles_error;
691  Eigen::Vector3d xyz_rotation;
692  if (parameterization_type_ == moveit_msgs::msg::OrientationConstraint::XYZ_EULER_ANGLES)
693  {
694  euler_angles_error = CalcEulerAngles(diff.linear());
695  // Converting from a rotation matrix to intrinsic XYZ Euler angles has 2 singularities:
696  // pitch ~= pi/2 ==> roll + yaw = theta
697  // pitch ~= -pi/2 ==> roll - yaw = theta
698  // in those cases CalcEulerAngles will set roll (xyz_rotation(0)) to theta and yaw (xyz_rotation(2)) to zero, so for
699  // us to be able to capture yaw tolerance violations we do the following: If theta violates the absolute yaw
700  // tolerance we think of it as a pure yaw rotation and set roll to zero.
701  xyz_rotation = std::get<Eigen::Vector3d>(euler_angles_error);
702  if (!std::get<bool>(euler_angles_error))
703  {
704  if (normalizeAbsoluteAngle(xyz_rotation(0)) > absolute_z_axis_tolerance_ + std::numeric_limits<double>::epsilon())
705  {
706  xyz_rotation(2) = xyz_rotation(0);
707  xyz_rotation(0) = 0;
708  }
709  }
710  // Account for angle wrapping
711  xyz_rotation = xyz_rotation.unaryExpr(&normalizeAbsoluteAngle);
712  }
713  else if (parameterization_type_ == moveit_msgs::msg::OrientationConstraint::ROTATION_VECTOR)
714  {
715  Eigen::AngleAxisd aa(diff.linear());
716  xyz_rotation = aa.axis() * aa.angle();
717  xyz_rotation(0) = fabs(xyz_rotation(0));
718  xyz_rotation(1) = fabs(xyz_rotation(1));
719  xyz_rotation(2) = fabs(xyz_rotation(2));
720  }
721  else
722  {
723  /* The parameterization type should be validated in configure, so this should never happen. */
724  RCLCPP_ERROR(LOGGER, "The parameterization type for the orientation constraints is invalid.");
725  }
726 
727  bool result = xyz_rotation(2) < absolute_z_axis_tolerance_ + std::numeric_limits<double>::epsilon() &&
728  xyz_rotation(1) < absolute_y_axis_tolerance_ + std::numeric_limits<double>::epsilon() &&
729  xyz_rotation(0) < absolute_x_axis_tolerance_ + std::numeric_limits<double>::epsilon();
730 
731  if (verbose)
732  {
733  Eigen::Quaterniond q_act(state.getGlobalLinkTransform(link_model_).linear());
734  Eigen::Quaterniond q_des(desired_rotation_matrix_);
735  RCLCPP_INFO(LOGGER,
736  "Orientation constraint %s for link '%s'. Quaternion desired: %f %f %f %f, quaternion "
737  "actual: %f %f %f %f, error: x=%f, y=%f, z=%f, tolerance: x=%f, y=%f, z=%f",
738  result ? "satisfied" : "violated", link_model_->getName().c_str(), q_des.x(), q_des.y(), q_des.z(),
739  q_des.w(), q_act.x(), q_act.y(), q_act.z(), q_act.w(), xyz_rotation(0), xyz_rotation(1),
741  }
742 
743  return ConstraintEvaluationResult(result, constraint_weight_ * (xyz_rotation(0) + xyz_rotation(1) + xyz_rotation(2)));
744 }
745 
746 void OrientationConstraint::print(std::ostream& out) const
747 {
748  if (link_model_)
749  {
750  out << "Orientation constraint on link '" << link_model_->getName() << "'" << '\n';
751  Eigen::Quaterniond q_des(desired_rotation_matrix_);
752  out << "Desired orientation:" << q_des.x() << "," << q_des.y() << "," << q_des.z() << "," << q_des.w() << '\n';
753  }
754  else
755  out << "No constraint" << '\n';
756 }
757 
758 VisibilityConstraint::VisibilityConstraint(const moveit::core::RobotModelConstPtr& model)
759  : KinematicConstraint(model), collision_env_(std::make_shared<collision_detection::CollisionEnvFCL>(model))
760 {
762 }
763 
765 {
766  mobile_sensor_frame_ = false;
767  mobile_target_frame_ = false;
768  target_frame_id_ = "";
769  sensor_frame_id_ = "";
770  sensor_pose_ = Eigen::Isometry3d::Identity();
772  target_pose_ = Eigen::Isometry3d::Identity();
773  cone_sides_ = 0;
774  points_.clear();
775  target_radius_ = -1.0;
776  max_view_angle_ = 0.0;
777  max_range_angle_ = 0.0;
778 }
779 
780 bool VisibilityConstraint::configure(const moveit_msgs::msg::VisibilityConstraint& vc,
781  const moveit::core::Transforms& tf)
782 {
783  clear();
784  target_radius_ = fabs(vc.target_radius);
785 
786  if (vc.target_radius <= std::numeric_limits<double>::epsilon())
787  RCLCPP_WARN(LOGGER, "The radius of the target disc that must be visible should be strictly positive");
788 
789  if (vc.cone_sides < 3)
790  {
791  RCLCPP_WARN(LOGGER,
792  "The number of sides for the visibility region must be 3 or more. "
793  "Assuming 3 sides instead of the specified %d",
794  vc.cone_sides);
795  cone_sides_ = 3;
796  }
797  else
798  cone_sides_ = vc.cone_sides;
799 
800  // compute the points on the base circle of the cone that make up the cone sides
801  points_.clear();
802  double delta = 2.0 * M_PI / (double)cone_sides_;
803  double a = 0.0;
804  for (unsigned int i = 0; i < cone_sides_; ++i, a += delta)
805  {
806  double x = sin(a) * target_radius_;
807  double y = cos(a) * target_radius_;
808  points_.push_back(Eigen::Vector3d(x, y, 0.0));
809  }
810 
811  tf2::fromMsg(vc.target_pose.pose, target_pose_);
812  ASSERT_ISOMETRY(target_pose_) // unsanitized input, could contain a non-isometry
813 
814  if (tf.isFixedFrame(vc.target_pose.header.frame_id))
815  {
816  tf.transformPose(vc.target_pose.header.frame_id, target_pose_, target_pose_);
818  mobile_target_frame_ = false;
819  // transform won't change, so apply it now
820  for (Eigen::Vector3d& point : points_)
821  point = target_pose_ * point;
822  }
823  else
824  {
825  target_frame_id_ = vc.target_pose.header.frame_id;
826  mobile_target_frame_ = true;
827  }
828 
829  tf2::fromMsg(vc.sensor_pose.pose, sensor_pose_);
830  ASSERT_ISOMETRY(sensor_pose_) // unsanitized input, could contain a non-isometry
831 
832  if (tf.isFixedFrame(vc.sensor_pose.header.frame_id))
833  {
834  tf.transformPose(vc.sensor_pose.header.frame_id, sensor_pose_, sensor_pose_);
836  mobile_sensor_frame_ = false;
837  }
838  else
839  {
840  sensor_frame_id_ = vc.sensor_pose.header.frame_id;
841  mobile_sensor_frame_ = true;
842  }
843 
844  if (vc.weight <= std::numeric_limits<double>::epsilon())
845  {
846  RCLCPP_WARN(LOGGER, "The weight of visibility constraint is near zero. Setting to 1.0.");
847  constraint_weight_ = 1.0;
848  }
849  else
850  constraint_weight_ = vc.weight;
851 
852  max_view_angle_ = vc.max_view_angle;
853  max_range_angle_ = vc.max_range_angle;
854  sensor_view_direction_ = vc.sensor_view_direction;
855 
856  return target_radius_ > std::numeric_limits<double>::epsilon();
857 }
858 
859 bool VisibilityConstraint::equal(const KinematicConstraint& other, double margin) const
860 {
861  if (other.getType() != type_)
862  return false;
863  const VisibilityConstraint& o = static_cast<const VisibilityConstraint&>(other);
864 
868  {
869  if (fabs(max_view_angle_ - o.max_view_angle_) > margin || fabs(target_radius_ - o.target_radius_) > margin)
870  return false;
871  // sensor_pose_ is valid isometry, checked in configure()
872  Eigen::Isometry3d diff = sensor_pose_.inverse() * o.sensor_pose_; // valid isometry
873  if (diff.translation().norm() > margin)
874  return false;
875  if (!diff.linear().isIdentity(margin))
876  return false;
877  // target_pose_ is valid isometry, checked in configure()
878  diff = target_pose_.inverse() * o.target_pose_; // valid isometry
879  if (diff.translation().norm() > margin)
880  return false;
881  if (!diff.linear().isIdentity(margin))
882  return false;
883  return true;
884  }
885  return false;
886 }
887 
889 {
890  return target_radius_ > std::numeric_limits<double>::epsilon();
891 }
892 
894 {
895  // the current pose of the sensor
896 
897  const Eigen::Isometry3d& sp =
899  const Eigen::Isometry3d& tp =
901 
902  // transform the points on the disc to the desired target frame
903  const EigenSTL::vector_Vector3d* points = &points_;
904  std::unique_ptr<EigenSTL::vector_Vector3d> temp_points;
906  {
907  temp_points = std::make_unique<EigenSTL::vector_Vector3d>(points_.size());
908  for (std::size_t i = 0; i < points_.size(); ++i)
909  temp_points->at(i) = tp * points_[i];
910  points = temp_points.get();
911  }
912 
913  // allocate memory for a mesh to represent the visibility cone
914  shapes::Mesh* m = new shapes::Mesh();
915  m->vertex_count = cone_sides_ + 2;
916  m->vertices = new double[m->vertex_count * 3];
917  m->triangle_count = cone_sides_ * 2;
918  m->triangles = new unsigned int[m->triangle_count * 3];
919  // we do NOT allocate normals because we do not compute them
920 
921  // the sensor origin
922  m->vertices[0] = sp.translation().x();
923  m->vertices[1] = sp.translation().y();
924  m->vertices[2] = sp.translation().z();
925 
926  // the center of the base of the cone approximation
927  m->vertices[3] = tp.translation().x();
928  m->vertices[4] = tp.translation().y();
929  m->vertices[5] = tp.translation().z();
930 
931  // the points that approximate the base disc
932  for (std::size_t i = 0; i < points->size(); ++i)
933  {
934  m->vertices[i * 3 + 6] = points->at(i).x();
935  m->vertices[i * 3 + 7] = points->at(i).y();
936  m->vertices[i * 3 + 8] = points->at(i).z();
937  }
938 
939  // add the triangles
940  std::size_t p3 = points->size() * 3;
941  for (std::size_t i = 1; i < points->size(); ++i)
942  {
943  // triangle forming a side of the cone, using the sensor origin
944  std::size_t i3 = (i - 1) * 3;
945  m->triangles[i3] = i + 1;
946  m->triangles[i3 + 1] = 0;
947  m->triangles[i3 + 2] = i + 2;
948  // triangle forming a part of the base of the cone, using the center of the base
949  std::size_t i6 = p3 + i3;
950  m->triangles[i6] = i + 1;
951  m->triangles[i6 + 1] = 1;
952  m->triangles[i6 + 2] = i + 2;
953  }
954 
955  // last triangles
956  m->triangles[p3 - 3] = points->size() + 1;
957  m->triangles[p3 - 2] = 0;
958  m->triangles[p3 - 1] = 2;
959  p3 *= 2;
960  m->triangles[p3 - 3] = points->size() + 1;
961  m->triangles[p3 - 2] = 1;
962  m->triangles[p3 - 1] = 2;
963 
964  return m;
965 }
966 
968  visualization_msgs::msg::MarkerArray& markers) const
969 {
970  shapes::Mesh* m = getVisibilityCone(state);
971  visualization_msgs::msg::Marker mk;
972  shapes::constructMarkerFromShape(m, mk);
973  delete m;
974  mk.header.frame_id = robot_model_->getModelFrame();
975  mk.header.stamp = rclcpp::Clock().now();
976  mk.ns = "constraints";
977  mk.id = 1;
978  mk.action = visualization_msgs::msg::Marker::ADD;
979  mk.pose.position.x = 0;
980  mk.pose.position.y = 0;
981  mk.pose.position.z = 0;
982  mk.pose.orientation.x = 0;
983  mk.pose.orientation.y = 0;
984  mk.pose.orientation.z = 0;
985  mk.pose.orientation.w = 1;
986  mk.lifetime = rclcpp::Duration::from_seconds(60);
987  // this scale necessary to make results look reasonable
988  mk.scale.x = .01;
989  mk.color.a = 1.0;
990  mk.color.r = 1.0;
991  mk.color.g = 0.0;
992  mk.color.b = 0.0;
993 
994  markers.markers.push_back(mk);
995 
996  // getFrameTransform() returns a valid isometry by contract
997  // sensor_pose_ is valid isometry (checked in configure())
998  const Eigen::Isometry3d& sp =
1000  // target_pose_ is valid isometry (checked in configure())
1001  const Eigen::Isometry3d& tp =
1003 
1004  visualization_msgs::msg::Marker mka;
1005  mka.type = visualization_msgs::msg::Marker::ARROW;
1006  mka.action = visualization_msgs::msg::Marker::ADD;
1007  mka.color = mk.color;
1008  mka.pose = mk.pose;
1009 
1010  mka.header = mk.header;
1011  mka.ns = mk.ns;
1012  mka.id = 2;
1013  mka.lifetime = mk.lifetime;
1014  mka.scale.x = 0.05;
1015  mka.scale.y = .15;
1016  mka.scale.z = 0.0;
1017  mka.points.resize(2);
1018  Eigen::Vector3d d = tp.translation() + tp.linear().col(2) * 0.5;
1019  mka.points[0].x = tp.translation().x();
1020  mka.points[0].y = tp.translation().y();
1021  mka.points[0].z = tp.translation().z();
1022  mka.points[1].x = d.x();
1023  mka.points[1].y = d.y();
1024  mka.points[1].z = d.z();
1025  markers.markers.push_back(mka);
1026 
1027  mka.id = 3;
1028  mka.color.b = 1.0;
1029  mka.color.r = 0.0;
1030 
1031  d = sp.translation() + sp.linear().col(2 - sensor_view_direction_) * 0.5;
1032  mka.points[0].x = sp.translation().x();
1033  mka.points[0].y = sp.translation().y();
1034  mka.points[0].z = sp.translation().z();
1035  mka.points[1].x = d.x();
1036  mka.points[1].y = d.y();
1037  mka.points[1].z = d.z();
1038 
1039  markers.markers.push_back(mka);
1040 }
1041 
1043 {
1044  if (target_radius_ <= std::numeric_limits<double>::epsilon())
1045  return ConstraintEvaluationResult(true, 0.0);
1046 
1047  if (max_view_angle_ > 0.0 || max_range_angle_ > 0.0)
1048  {
1049  // getFrameTransform() returns a valid isometry by contract
1050  // sensor_pose_ is valid isometry (checked in configure())
1051  const Eigen::Isometry3d& sp =
1053  // target_pose_ is valid isometry (checked in configure())
1054  const Eigen::Isometry3d& tp =
1056 
1057  // necessary to do subtraction as SENSOR_Z is 0 and SENSOR_X is 2
1058  const Eigen::Vector3d& normal2 = sp.linear().col(2 - sensor_view_direction_);
1059 
1060  if (max_view_angle_ > 0.0)
1061  {
1062  const Eigen::Vector3d& normal1 = tp.linear().col(2) * -1.0; // along Z axis and inverted
1063  double dp = normal2.dot(normal1);
1064  double ang = acos(dp);
1065  if (dp < 0.0)
1066  {
1067  if (verbose)
1068  RCLCPP_INFO(LOGGER, "Visibility constraint is violated because the sensor is looking at "
1069  "the wrong side");
1070  return ConstraintEvaluationResult(false, 0.0);
1071  }
1072  if (max_view_angle_ < ang)
1073  {
1074  if (verbose)
1075  RCLCPP_INFO(LOGGER,
1076  "Visibility constraint is violated because the view angle is %lf "
1077  "(above the maximum allowed of %lf)",
1078  ang, max_view_angle_);
1079  return ConstraintEvaluationResult(false, 0.0);
1080  }
1081  }
1082  if (max_range_angle_ > 0.0)
1083  {
1084  const Eigen::Vector3d& dir = (tp.translation() - sp.translation()).normalized();
1085  double dp = normal2.dot(dir);
1086  if (dp < 0.0)
1087  {
1088  if (verbose)
1089  RCLCPP_INFO(LOGGER, "Visibility constraint is violated because the sensor is looking at "
1090  "the wrong side");
1091  return ConstraintEvaluationResult(false, 0.0);
1092  }
1093 
1094  double ang = acos(dp);
1095  if (max_range_angle_ < ang)
1096  {
1097  if (verbose)
1098  RCLCPP_INFO(LOGGER,
1099  "Visibility constraint is violated because the range angle is %lf "
1100  "(above the maximum allowed of %lf)",
1101  ang, max_range_angle_);
1102  return ConstraintEvaluationResult(false, 0.0);
1103  }
1104  }
1105  }
1106 
1107  shapes::Mesh* m = getVisibilityCone(state);
1108  if (!m)
1109  return ConstraintEvaluationResult(false, 0.0);
1110 
1111  // add the visibility cone as an object
1112  collision_env_->getWorld()->addToObject("cone", shapes::ShapeConstPtr(m), Eigen::Isometry3d::Identity());
1113 
1114  // check for collisions between the robot and the cone
1119  return decideContact(contact);
1120  };
1121  acm.setDefaultEntry(std::string("cone"), fn);
1122 
1123  req.contacts = true;
1124  req.verbose = verbose;
1125  req.max_contacts = 1;
1126  collision_env_->checkRobotCollision(req, res, state, acm);
1127 
1128  if (verbose)
1129  {
1130  std::stringstream ss;
1131  m->print(ss);
1132  RCLCPP_INFO(LOGGER, "Visibility constraint %ssatisfied. Visibility cone approximation:\n %s",
1133  res.collision ? "not " : "", ss.str().c_str());
1134  }
1135 
1136  collision_env_->getWorld()->removeObject("cone");
1137 
1138  return ConstraintEvaluationResult(!res.collision, res.collision ? res.contacts.begin()->second.front().depth : 0.0);
1139 }
1140 
1142 {
1145  return true;
1150  {
1151  RCLCPP_DEBUG(LOGGER, "Accepted collision with either sensor or target");
1152  return true;
1153  }
1158  {
1159  RCLCPP_DEBUG(LOGGER, "Accepted collision with either sensor or target");
1160  return true;
1161  }
1162  return false;
1163 }
1164 
1165 void VisibilityConstraint::print(std::ostream& out) const
1166 {
1167  if (enabled())
1168  {
1169  out << "Visibility constraint for sensor in frame '" << sensor_frame_id_ << "' using target in frame '"
1170  << target_frame_id_ << "'" << '\n';
1171  out << "Target radius: " << target_radius_ << ", using " << cone_sides_ << " sides." << '\n';
1172  }
1173  else
1174  out << "No constraint" << '\n';
1175 }
1176 
1178 {
1179  all_constraints_ = moveit_msgs::msg::Constraints();
1180  kinematic_constraints_.clear();
1181  joint_constraints_.clear();
1182  position_constraints_.clear();
1183  orientation_constraints_.clear();
1184  visibility_constraints_.clear();
1185 }
1186 
1187 bool KinematicConstraintSet::add(const std::vector<moveit_msgs::msg::JointConstraint>& jc)
1188 {
1189  bool result = true;
1190  for (const moveit_msgs::msg::JointConstraint& joint_constraint : jc)
1191  {
1193  bool u = ev->configure(joint_constraint);
1194  result = result && u;
1195  kinematic_constraints_.push_back(KinematicConstraintPtr(ev));
1196  joint_constraints_.push_back(joint_constraint);
1197  all_constraints_.joint_constraints.push_back(joint_constraint);
1198  }
1199  return result;
1200 }
1201 
1202 bool KinematicConstraintSet::add(const std::vector<moveit_msgs::msg::PositionConstraint>& pc,
1203  const moveit::core::Transforms& tf)
1204 {
1205  bool result = true;
1206  for (const moveit_msgs::msg::PositionConstraint& position_constraint : pc)
1207  {
1209  bool u = ev->configure(position_constraint, tf);
1210  result = result && u;
1211  kinematic_constraints_.push_back(KinematicConstraintPtr(ev));
1212  position_constraints_.push_back(position_constraint);
1213  all_constraints_.position_constraints.push_back(position_constraint);
1214  }
1215  return result;
1216 }
1217 
1218 bool KinematicConstraintSet::add(const std::vector<moveit_msgs::msg::OrientationConstraint>& oc,
1219  const moveit::core::Transforms& tf)
1220 {
1221  bool result = true;
1222  for (const moveit_msgs::msg::OrientationConstraint& orientation_constraint : oc)
1223  {
1225  bool u = ev->configure(orientation_constraint, tf);
1226  result = result && u;
1227  kinematic_constraints_.push_back(KinematicConstraintPtr(ev));
1228  orientation_constraints_.push_back(orientation_constraint);
1229  all_constraints_.orientation_constraints.push_back(orientation_constraint);
1230  }
1231  return result;
1232 }
1233 
1234 bool KinematicConstraintSet::add(const std::vector<moveit_msgs::msg::VisibilityConstraint>& vc,
1235  const moveit::core::Transforms& tf)
1236 {
1237  bool result = true;
1238  for (const moveit_msgs::msg::VisibilityConstraint& visibility_constraint : vc)
1239  {
1241  bool u = ev->configure(visibility_constraint, tf);
1242  result = result && u;
1243  kinematic_constraints_.push_back(KinematicConstraintPtr(ev));
1244  visibility_constraints_.push_back(visibility_constraint);
1245  all_constraints_.visibility_constraints.push_back(visibility_constraint);
1246  }
1247  return result;
1248 }
1249 
1250 bool KinematicConstraintSet::add(const moveit_msgs::msg::Constraints& c, const moveit::core::Transforms& tf)
1251 {
1252  bool j = add(c.joint_constraints);
1253  bool p = add(c.position_constraints, tf);
1254  bool o = add(c.orientation_constraints, tf);
1255  bool v = add(c.visibility_constraints, tf);
1256  return j && p && o && v;
1257 }
1258 
1260 {
1261  ConstraintEvaluationResult res(true, 0.0);
1262  for (const KinematicConstraintPtr& kinematic_constraint : kinematic_constraints_)
1263  {
1264  ConstraintEvaluationResult r = kinematic_constraint->decide(state, verbose);
1265  if (!r.satisfied)
1266  res.satisfied = false;
1267  res.distance += r.distance;
1268  }
1269  return res;
1270 }
1271 
1273  std::vector<ConstraintEvaluationResult>& results,
1274  bool verbose) const
1275 {
1276  ConstraintEvaluationResult result(true, 0.0);
1277  results.resize(kinematic_constraints_.size());
1278  for (std::size_t i = 0; i < kinematic_constraints_.size(); ++i)
1279  {
1280  results[i] = kinematic_constraints_[i]->decide(state, verbose);
1281  result.satisfied = result.satisfied && results[i].satisfied;
1282  result.distance += results[i].distance;
1283  }
1284 
1285  return result;
1286 }
1287 
1288 void KinematicConstraintSet::print(std::ostream& out) const
1289 {
1290  out << kinematic_constraints_.size() << " kinematic constraints" << '\n';
1291  for (const KinematicConstraintPtr& kinematic_constraint : kinematic_constraints_)
1292  kinematic_constraint->print(out);
1293 }
1294 
1295 bool KinematicConstraintSet::equal(const KinematicConstraintSet& other, double margin) const
1296 {
1297  // each constraint in this matches some in the other
1298  for (const KinematicConstraintPtr& kinematic_constraint : kinematic_constraints_)
1299  {
1300  bool found = false;
1301  for (unsigned int j = 0; !found && j < other.kinematic_constraints_.size(); ++j)
1302  found = kinematic_constraint->equal(*other.kinematic_constraints_[j], margin);
1303  if (!found)
1304  return false;
1305  }
1306  // each constraint in the other matches some constraint in this
1307  for (const KinematicConstraintPtr& kinematic_constraint : other.kinematic_constraints_)
1308  {
1309  bool found = false;
1310  for (unsigned int j = 0; !found && j < kinematic_constraints_.size(); ++j)
1311  found = kinematic_constraint->equal(*kinematic_constraints_[j], margin);
1312  if (!found)
1313  return false;
1314  }
1315  return true;
1316 }
1317 
1318 } // end of namespace kinematic_constraints
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
void setDefaultEntry(const std::string &name, bool allowed)
Set the default value for entries that include name but are not set explicitly with setEntry().
Class for handling single DOF joint constraints.
double joint_tolerance_below_
Position and tolerance values.
std::string joint_variable_name_
The joint variable name.
bool equal(const KinematicConstraint &other, double margin) const override
Check if two joint constraints are the same.
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const override
Decide whether the constraint is satisfied in the indicated state.
int joint_variable_index_
The index of the joint variable name in the full robot state.
bool joint_is_continuous_
Whether or not the joint is continuous.
void clear() override
Clear the stored constraint.
bool configure(const moveit_msgs::msg::JointConstraint &jc)
Configure the constraint based on a moveit_msgs::msg::JointConstraint.
const moveit::core::JointModel * joint_model_
The joint from the kinematic model for this constraint.
bool enabled() const override
This function returns true if this constraint is configured and able to decide whether states do meet...
void print(std::ostream &out=std::cout) const override
Print the constraint data.
std::string local_variable_name_
The local variable name for a multi DOF joint, if any.
A class that contains many different constraints, and can check RobotState *versus the full set....
void print(std::ostream &out=std::cout) const
Print the constraint data.
bool equal(const KinematicConstraintSet &other, double margin) const
Whether or not another KinematicConstraintSet is equal to this one.
std::vector< moveit_msgs::msg::VisibilityConstraint > visibility_constraints_
Messages corresponding to all internal visibility constraints.
std::vector< moveit_msgs::msg::OrientationConstraint > orientation_constraints_
Messages corresponding to all internal orientation constraints.
moveit::core::RobotModelConstPtr robot_model_
The kinematic model used for by the Set.
bool add(const moveit_msgs::msg::Constraints &c, const moveit::core::Transforms &tf)
Add all known constraints.
moveit_msgs::msg::Constraints all_constraints_
Messages corresponding to all internal constraints.
std::vector< moveit_msgs::msg::PositionConstraint > position_constraints_
Messages corresponding to all internal position constraints.
std::vector< KinematicConstraintPtr > kinematic_constraints_
Shared pointers to all the member constraints.
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const
Determines whether all constraints are satisfied by state, returning a single evaluation result.
std::vector< moveit_msgs::msg::JointConstraint > joint_constraints_
Messages corresponding to all internal joint constraints.
Base class for representing a kinematic constraint.
double constraint_weight_
The weight of a constraint is a multiplicative factor associated to the distance computed by the deci...
ConstraintType type_
The type of the constraint.
ConstraintType getType() const
Get the type of constraint.
KinematicConstraint(const moveit::core::RobotModelConstPtr &model)
Constructor.
moveit::core::RobotModelConstPtr robot_model_
The kinematic model associated with this constraint.
Class for constraints on the orientation of a link.
bool mobile_frame_
Whether or not the header frame is mobile or fixed.
void clear() override
Clear the stored constraint.
bool equal(const KinematicConstraint &other, double margin) const override
Check if two orientation constraints are the same.
void print(std::ostream &out=std::cout) const override
Print the constraint data.
std::string desired_rotation_frame_id_
The target frame of the transform tree.
bool configure(const moveit_msgs::msg::OrientationConstraint &oc, const moveit::core::Transforms &tf)
Configure the constraint based on a moveit_msgs::msg::OrientationConstraint.
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const override
Decide whether the constraint is satisfied in the indicated state.
double absolute_z_axis_tolerance_
Storage for the tolerances.
Eigen::Matrix3d desired_rotation_matrix_inv_
The inverse of the desired rotation matrix, precomputed for efficiency. Guaranteed to be valid rotati...
bool enabled() const override
This function returns true if this constraint is configured and able to decide whether states do meet...
Eigen::Matrix3d desired_rotation_matrix_
The desired rotation matrix in the tf frame. Guaranteed to be valid rotation matrix.
const moveit::core::LinkModel * link_model_
The target link model.
int parameterization_type_
Parameterization type for orientation tolerance.
Class for constraints on the XYZ position of a link.
void print(std::ostream &out=std::cout) const override
Print the constraint data.
bool enabled() const override
This function returns true if this constraint is configured and able to decide whether states do meet...
std::string constraint_frame_id_
The constraint frame id.
void clear() override
Clear the stored constraint.
bool configure(const moveit_msgs::msg::PositionConstraint &pc, const moveit::core::Transforms &tf)
Configure the constraint based on a moveit_msgs::msg::PositionConstraint.
std::vector< bodies::BodyPtr > constraint_region_
The constraint region vector.
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const override
Decide whether the constraint is satisfied in the indicated state.
bool equal(const KinematicConstraint &other, double margin) const override
Check if two constraints are the same. For position constraints this means that:
const moveit::core::LinkModel * link_model_
The link model constraint subject.
bool has_offset_
Whether the offset is substantially different than 0.0.
Eigen::Vector3d offset_
The target offset.
EigenSTL::vector_Isometry3d constraint_region_pose_
The constraint region pose vector. All isometries are guaranteed to be valid.
bool mobile_frame_
Whether or not a mobile frame is employed.
Class for constraints on the visibility relationship between a sensor and a target.
Eigen::Isometry3d target_pose_
The target pose transformed into the transform frame.
void clear() override
Clear the stored constraint.
bool equal(const KinematicConstraint &other, double margin) const override
Check if two constraints are the same.
Eigen::Isometry3d sensor_pose_
The sensor pose transformed into the transform frame.
void print(std::ostream &out=std::cout) const override
Print the constraint data.
bool enabled() const override
This function returns true if this constraint is configured and able to decide whether states do meet...
VisibilityConstraint(const moveit::core::RobotModelConstPtr &model)
Constructor.
std::string target_frame_id_
The target frame id.
double max_range_angle_
Storage for the max range angle.
bool mobile_sensor_frame_
True if the sensor is a non-fixed frame relative to the transform frame.
std::string sensor_frame_id_
The sensor frame id.
double max_view_angle_
Storage for the max view angle.
double target_radius_
Storage for the target radius.
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const override
Decide whether the constraint is satisfied in the indicated state.
void getMarkers(const moveit::core::RobotState &state, visualization_msgs::msg::MarkerArray &markers) const
Adds markers associated with the visibility cone, sensor and target to the visualization array.
bool configure(const moveit_msgs::msg::VisibilityConstraint &vc, const moveit::core::Transforms &tf)
Configure the constraint based on a moveit_msgs::msg::VisibilityConstraint.
EigenSTL::vector_Vector3d points_
A set of points along the base of the circle.
int sensor_view_direction_
Storage for the sensor view direction.
bool mobile_target_frame_
True if the target is a non-fixed frame relative to the transform frame.
unsigned int cone_sides_
Storage for the cone sides
shapes::Mesh * getVisibilityCone(const moveit::core::RobotState &state) const
Gets a trimesh shape representing the visibility cone.
bool decideContact(const collision_detection::Contact &contact) const
Function that gets passed into collision checking to allow some collisions.
collision_detection::CollisionEnvPtr collision_env_
A copy of the collision robot maintained for collision checking the cone against robot links.
const std::vector< std::string > & getLocalVariableNames() const
Get the local names of the variable that make up the joint (suffixes that are attached to joint names...
Definition: joint_model.h:198
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 VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a variable. Throw an exception if the variable was not found.
JointType getType() const
Get the type of joint.
Definition: joint_model.h:151
const std::string & getName() const
The name of this link.
Definition: link_model.h:86
bool isContinuous() const
Check if this joint wraps around.
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
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...
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
Provides an implementation of a snapshot of a transform tree that can be easily queried for transform...
Definition: transforms.h:59
const std::string & getTargetFrame() const
Get the planning frame corresponding to this set of transforms.
Definition: transforms.cpp:73
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
void transformPose(const std::string &from_frame, const Eigen::Isometry3d &t_in, Eigen::Isometry3d &t_out) const
Transform a pose in from_frame to the target_frame.
Definition: transforms.h:184
void transformQuaternion(const std::string &from_frame, const Eigen::Quaterniond &q_in, Eigen::Quaterniond &q_out) const
Transform a quaternion in from_frame to the target_frame.
Definition: transforms.h:159
virtual bool isFixedFrame(const std::string &frame) const
Check whether a frame stays constant as the state of the robot model changes. This is true for any tr...
Definition: transforms.cpp:92
@ ROBOT_LINK
A link on the robot.
@ ROBOT_ATTACHED
A body attached to a robot link.
@ WORLD_OBJECT
A body in the environment.
std::function< bool(collision_detection::Contact &)> DecideContactFn
Signature of predicate that decides whether a contact is allowed or not (when AllowedCollision::Type ...
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
Representation and evaluation of kinematic constraints.
std::tuple< Eigen::Matrix< typename Eigen::MatrixBase< Derived >::Scalar, 3, 1 >, bool > CalcEulerAngles(const Eigen::MatrixBase< Derived > &R)
p
Definition: pick.py:62
x
Definition: pick.py:64
y
Definition: pick.py:65
a
Definition: plan.py:54
r
Definition: plan.py:56
d
Definition: setup.py:4
name
Definition: setup.py:7
Representation of a collision checking request.
bool verbose
Flag indicating whether information about detected collisions should be reported.
bool contacts
If true, compute contacts. Otherwise only a binary collision yes/no is reported.
std::size_t max_contacts
Overall maximum number of contacts to compute.
Representation of a collision checking result.
ContactMap contacts
A map returning the pairs of body ids in contact, plus their contact details.
bool collision
True if collision was found, false otherwise.
Definition of a contact point.
std::string body_name_2
The id of the second body involved in the contact.
std::string body_name_1
The id of the first body involved in the contact.
BodyType body_type_1
The type of the first body involved in the contact.
BodyType body_type_2
The type of the second body involved in the contact.
Struct for containing the results of constraint evaluation.
bool satisfied
Whether or not the constraint or constraints were satisfied.
double distance
The distance evaluation from the constraint or constraints.