43 #include <boost/math/constants/constants.hpp>
53 double v = fmod(angle, 2.0 * boost::math::constants::pi<double>());
54 if (v < -boost::math::constants::pi<double>())
55 v += 2.0 * boost::math::constants::pi<double>();
56 else if (v > boost::math::constants::pi<double>())
57 v -= 2.0 * boost::math::constants::pi<double>();
65 const double normalized_angle = std::fmod(std::abs(angle), 2 * M_PI);
66 return std::min(2 * M_PI - normalized_angle, normalized_angle);
76 template <
typename Derived>
77 std::tuple<Eigen::Matrix<typename Eigen::MatrixBase<Derived>::Scalar, 3, 1>,
bool>
82 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Derived, 3, 3)
83 using Index = EIGEN_DEFAULT_DENSE_INDEX_TYPE;
84 using Scalar = typename
Eigen::MatrixBase<Derived>::Scalar;
88 Eigen::Matrix<Scalar, 3, 1> res;
89 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);
90 res[1] = atan2(R(i, k), rsum);
92 if (rsum > 4 *
Eigen::NumTraits<Scalar>::epsilon())
94 res[0] = atan2(-R(j, k), R(k, k));
95 res[2] = atan2(-R(i, j), R(i, i));
100 const Scalar spos = R(j, i) + R(k, j);
101 const Scalar cpos = R(j, j) - R(k, i);
102 res[0] = atan2(spos, cpos);
104 return { res,
false };
106 const Scalar sneg = R(k, j) - R(j, i);
107 const Scalar cneg = R(j, j) + R(k, i);
108 res[0] = atan2(sneg, cneg);
110 return { res,
false };
114 : type_(UNKNOWN_CONSTRAINT), robot_model_(model), constraint_weight_(
std::numeric_limits<double>::
epsilon())
118 KinematicConstraint::~KinematicConstraint() =
default;
120 bool JointConstraint::configure(
const moveit_msgs::JointConstraint& jc)
126 if (jc.tolerance_above < 0.0 || jc.tolerance_below < 0.0)
128 ROS_WARN_NAMED(
"kinematic_constraints",
"JointConstraint tolerance values must be positive.");
129 joint_model_ =
nullptr;
133 joint_variable_name_ = jc.joint_name;
134 local_variable_name_.clear();
135 if (robot_model_->hasJointModel(joint_variable_name_))
136 joint_model_ = robot_model_->getJointModel(joint_variable_name_);
139 std::size_t pos = jc.joint_name.find_last_of(
'/');
140 if (pos != std::string::npos)
142 joint_model_ = robot_model_->getJointModel(jc.joint_name.substr(0, pos));
143 if (pos + 1 < jc.joint_name.length())
144 local_variable_name_ = jc.joint_name.substr(pos + 1);
147 joint_model_ = robot_model_->getJointModel(jc.joint_name);
152 if (local_variable_name_.empty())
155 if (joint_model_->getVariableCount() == 0)
157 ROS_ERROR_NAMED(
"kinematic_constraints",
"Joint '%s' has no parameters to constrain", jc.joint_name.c_str());
158 joint_model_ =
nullptr;
160 else if (joint_model_->getVariableCount() > 1)
163 "Joint '%s' has more than one parameter to constrain. "
164 "This type of constraint is not supported.",
165 jc.joint_name.c_str());
166 joint_model_ =
nullptr;
172 const std::vector<std::string>& local_var_names = joint_model_->getLocalVariableNames();
173 for (std::size_t i = 0; i < local_var_names.size(); ++i)
174 if (local_var_names[i] == local_variable_name_)
181 ROS_ERROR_NAMED(
"kinematic_constraints",
"Local variable name '%s' is not known to joint '%s'",
182 local_variable_name_.c_str(), joint_model_->getName().c_str());
183 joint_model_ =
nullptr;
190 joint_is_continuous_ =
false;
191 joint_tolerance_above_ = jc.tolerance_above;
192 joint_tolerance_below_ = jc.tolerance_below;
193 joint_variable_index_ = robot_model_->getVariableIndex(joint_variable_name_);
196 joint_is_continuous_ =
false;
202 joint_is_continuous_ =
true;
206 if (local_variable_name_ ==
"theta")
207 joint_is_continuous_ =
true;
210 if (joint_is_continuous_)
216 joint_position_ = jc.position;
219 if (bounds.
min_position_ > joint_position_ + joint_tolerance_above_)
222 joint_tolerance_above_ = std::numeric_limits<double>::epsilon();
224 "Joint %s is constrained to be below the minimum bound %g. "
225 "Assuming minimum bounds instead.",
228 else if (bounds.
max_position_ < joint_position_ - joint_tolerance_below_)
231 joint_tolerance_below_ = std::numeric_limits<double>::epsilon();
233 "Joint %s is constrained to be above the maximum bounds %g. "
234 "Assuming maximum bounds instead.",
239 if (jc.weight <= std::numeric_limits<double>::epsilon())
242 "The weight on constraint for joint '%s' is very near zero. Setting to 1.0.",
243 jc.joint_name.c_str());
244 constraint_weight_ = 1.0;
247 constraint_weight_ = jc.weight;
249 return joint_model_ !=
nullptr;
252 bool JointConstraint::equal(
const KinematicConstraint& other,
double margin)
const
254 if (other.getType() != type_)
256 const JointConstraint& o =
static_cast<const JointConstraint&
>(other);
257 if (o.joint_model_ == joint_model_ && o.local_variable_name_ == local_variable_name_)
258 return fabs(joint_position_ - o.joint_position_) <= margin &&
259 fabs(joint_tolerance_above_ - o.joint_tolerance_above_) <= margin &&
260 fabs(joint_tolerance_below_ - o.joint_tolerance_below_) <= margin;
267 return ConstraintEvaluationResult(
true, 0.0);
273 if (joint_is_continuous_)
277 if (dif > boost::math::constants::pi<double>())
278 dif = 2.0 * boost::math::constants::pi<double>() - dif;
279 else if (dif < -boost::math::constants::pi<double>())
280 dif += 2.0 * boost::math::constants::pi<double>();
283 dif = current_joint_position - joint_position_;
286 bool result = dif <= (joint_tolerance_above_ + 2.0 * std::numeric_limits<double>::epsilon()) &&
287 dif >= (-joint_tolerance_below_ - 2.0 * std::numeric_limits<double>::epsilon());
290 "Constraint %s:: Joint name: '%s', actual value: %f, desired value: %f, "
291 "tolerance_above: %f, tolerance_below: %f",
292 result ?
"satisfied" :
"violated", joint_variable_name_.c_str(), current_joint_position,
293 joint_position_, joint_tolerance_above_, joint_tolerance_below_);
297 bool JointConstraint::enabled()
const
302 void JointConstraint::clear()
304 joint_model_ =
nullptr;
305 joint_variable_index_ = -1;
306 joint_is_continuous_ =
false;
307 local_variable_name_ =
"";
308 joint_variable_name_ =
"";
309 joint_position_ = joint_tolerance_below_ = joint_tolerance_above_ = 0.0;
316 out <<
"Joint constraint for joint " << joint_variable_name_ <<
": " << std::endl;
318 out << joint_position_ <<
"; ";
319 out <<
" tolerance below = ";
320 out << joint_tolerance_below_ <<
"; ";
321 out <<
" tolerance above = ";
322 out << joint_tolerance_above_ <<
"; ";
326 out <<
"No constraint" << std::endl;
334 link_model_ = robot_model_->getLinkModel(pc.link_name);
335 if (link_model_ ==
nullptr)
338 "Position constraint link model %s not found in kinematic model. Constraint invalid.",
339 pc.link_name.c_str());
343 if (pc.header.frame_id.empty())
345 ROS_WARN_NAMED(
"kinematic_constraints",
"No frame specified for position constraint on link '%s'!",
346 pc.link_name.c_str());
350 offset_ =
Eigen::Vector3d(pc.target_point_offset.x, pc.target_point_offset.y, pc.target_point_offset.z);
351 has_offset_ = offset_.squaredNorm() > std::numeric_limits<double>::epsilon();
356 mobile_frame_ =
false;
360 constraint_frame_id_ = pc.header.frame_id;
361 mobile_frame_ =
true;
365 for (std::size_t i = 0; i < pc.constraint_region.primitives.size(); ++i)
370 if (pc.constraint_region.primitive_poses.size() <= i)
372 ROS_WARN_NAMED(
"kinematic_constraints",
"Constraint region message does not contain enough primitive poses");
378 constraint_region_pose_.push_back(
t);
380 tf.
transformPose(pc.header.frame_id, constraint_region_pose_.back(), constraint_region_pose_.back());
383 body->setDimensionsDirty(shape.get());
384 body->setPoseDirty(constraint_region_pose_.back());
385 body->updateInternalData();
386 constraint_region_.push_back(body);
389 ROS_WARN_NAMED(
"kinematic_constraints",
"Could not construct primitive shape %zu", i);
393 for (std::size_t i = 0; i < pc.constraint_region.meshes.size(); ++i)
398 if (pc.constraint_region.mesh_poses.size() <= i)
400 ROS_WARN_NAMED(
"kinematic_constraints",
"Constraint region message does not contain enough primitive poses");
406 constraint_region_pose_.push_back(t);
408 tf.
transformPose(pc.header.frame_id, constraint_region_pose_.back(), constraint_region_pose_.back());
410 body->setDimensionsDirty(shape.get());
411 body->setPoseDirty(constraint_region_pose_.back());
412 body->updateInternalData();
413 constraint_region_.push_back(body);
417 ROS_WARN_NAMED(
"kinematic_constraints",
"Could not construct mesh shape %zu", i);
421 if (pc.weight <= std::numeric_limits<double>::epsilon())
424 "The weight on position constraint for link '%s' is near zero. Setting to 1.0.",
425 pc.link_name.c_str());
426 constraint_weight_ = 1.0;
429 constraint_weight_ = pc.weight;
431 return !constraint_region_.empty();
434 bool PositionConstraint::equal(
const KinematicConstraint& other,
double margin)
const
436 if (other.getType() != type_)
438 const PositionConstraint& o =
static_cast<const PositionConstraint&
>(other);
442 if ((offset_ - o.offset_).norm() > margin)
444 std::vector<bool> other_region_matches_this(constraint_region_.size(),
false);
445 for (std::size_t i = 0; i < constraint_region_.size(); ++i)
447 bool some_match =
false;
449 for (std::size_t j = 0; j < o.constraint_region_.size(); ++j)
452 Eigen::Isometry3d diff = constraint_region_pose_[i].inverse() * o.constraint_region_pose_[j];
453 if (diff.translation().norm() < margin && diff.linear().isIdentity(margin) &&
454 constraint_region_[i]->getType() == o.constraint_region_[j]->getType() &&
455 fabs(constraint_region_[i]->computeVolume() - o.constraint_region_[j]->computeVolume()) < margin)
459 other_region_matches_this[j] =
true;
465 for (std::size_t i = 0; i < o.constraint_region_.size(); ++i)
466 if (!other_region_matches_this[i])
476 const std::string& name,
double weight,
477 bool result,
bool verbose)
479 double dx = desired.x() - pt.x();
480 double dy = desired.y() - pt.y();
481 double dz = desired.z() - pt.z();
485 "Position constraint %s on link '%s'. Desired: %f, %f, %f, current: %f, %f, %f",
486 result ?
"satisfied" :
"violated",
name.c_str(), desired.x(), desired.y(), desired.z(), pt.x(),
488 ROS_INFO_NAMED(
"kinematic_constraints",
"Differences %g %g %g", dx, dy, dz);
490 return ConstraintEvaluationResult(result, weight * sqrt(dx * dx + dy * dy + dz * dz));
495 if (!link_model_ || constraint_region_.empty())
496 return ConstraintEvaluationResult(
true, 0.0);
501 for (std::size_t i = 0; i < constraint_region_.size(); ++i)
503 Eigen::Isometry3d tmp = state.
getFrameTransform(constraint_frame_id_) * constraint_region_pose_[i];
504 bool result = constraint_region_[i]->cloneAt(tmp)->containsPoint(pt, verbose);
505 if (result || (i + 1 == constraint_region_pose_.size()))
515 for (std::size_t i = 0; i < constraint_region_.size(); ++i)
517 bool result = constraint_region_[i]->containsPoint(pt,
true);
518 if (result || (i + 1 == constraint_region_.size()))
520 link_model_->getName(), constraint_weight_, result, verbose);
523 constraint_weight_, result, verbose);
532 out <<
"Position constraint on link '" << link_model_->getName() <<
"'" << std::endl;
534 out <<
"No constraint" << std::endl;
537 void PositionConstraint::clear()
541 constraint_region_.clear();
542 constraint_region_pose_.clear();
543 mobile_frame_ =
false;
544 constraint_frame_id_ =
"";
545 link_model_ =
nullptr;
548 bool PositionConstraint::enabled()
const
550 return link_model_ && !constraint_region_.empty();
553 bool OrientationConstraint::configure(
const moveit_msgs::OrientationConstraint& oc,
const moveit::core::Transforms& tf)
559 link_model_ = robot_model_->getLinkModel(oc.link_name, &found);
562 ROS_WARN_NAMED(
"kinematic_constraints",
"Could not find link model for link name '%s'", oc.link_name.c_str());
565 Eigen::Quaterniond q;
567 if (fabs(q.norm() - 1.0) > 1e-3)
570 "Orientation constraint for link '%s' is probably incorrect: %f, %f, %f, "
571 "%f. Assuming identity instead.",
572 oc.link_name.c_str(), oc.orientation.x, oc.orientation.y, oc.orientation.z, oc.orientation.w);
573 q = Eigen::Quaterniond(1.0, 0.0, 0.0, 0.0);
576 if (oc.header.frame_id.empty())
577 ROS_WARN_NAMED(
"kinematic_constraints",
"No frame specified for position constraint on link '%s'!",
578 oc.link_name.c_str());
580 desired_R_in_frame_id_ = Eigen::Quaterniond(q);
585 desired_rotation_matrix_ = Eigen::Matrix3d(q);
586 desired_rotation_matrix_inv_ = desired_rotation_matrix_.transpose();
587 mobile_frame_ =
false;
591 desired_rotation_frame_id_ = oc.header.frame_id;
592 desired_rotation_matrix_ = Eigen::Matrix3d(q);
593 mobile_frame_ =
true;
595 std::stringstream matrix_str;
596 matrix_str << desired_rotation_matrix_;
597 ROS_DEBUG_NAMED(
"kinematic_constraints",
"The desired rotation matrix for link '%s' in frame %s is:\n%s",
598 oc.link_name.c_str(), desired_rotation_frame_id_.c_str(), matrix_str.str().c_str());
600 if (oc.weight <= std::numeric_limits<double>::epsilon())
603 "The weight on position constraint for link '%s' is near zero. Setting to 1.0.",
604 oc.link_name.c_str());
605 constraint_weight_ = 1.0;
609 constraint_weight_ = oc.weight;
612 parameterization_type_ = oc.parameterization;
614 if (parameterization_type_ != moveit_msgs::OrientationConstraint::XYZ_EULER_ANGLES &&
615 parameterization_type_ != moveit_msgs::OrientationConstraint::ROTATION_VECTOR)
618 "Unknown parameterization for orientation constraint tolerance, using default (XYZ_EULER_ANGLES).");
619 parameterization_type_ = moveit_msgs::OrientationConstraint::XYZ_EULER_ANGLES;
622 absolute_x_axis_tolerance_ = fabs(oc.absolute_x_axis_tolerance);
623 if (absolute_x_axis_tolerance_ < std::numeric_limits<double>::epsilon())
624 ROS_WARN_NAMED(
"kinematic_constraints",
"Near-zero value for absolute_x_axis_tolerance");
625 absolute_y_axis_tolerance_ = fabs(oc.absolute_y_axis_tolerance);
626 if (absolute_y_axis_tolerance_ < std::numeric_limits<double>::epsilon())
627 ROS_WARN_NAMED(
"kinematic_constraints",
"Near-zero value for absolute_y_axis_tolerance");
628 absolute_z_axis_tolerance_ = fabs(oc.absolute_z_axis_tolerance);
629 if (absolute_z_axis_tolerance_ < std::numeric_limits<double>::epsilon())
630 ROS_WARN_NAMED(
"kinematic_constraints",
"Near-zero value for absolute_z_axis_tolerance");
632 return link_model_ !=
nullptr;
635 bool OrientationConstraint::equal(
const KinematicConstraint& other,
double margin)
const
637 if (other.getType() != type_)
639 const OrientationConstraint& o =
static_cast<const OrientationConstraint&
>(other);
641 if (o.link_model_ == link_model_ &&
644 if (!desired_rotation_matrix_.isApprox(o.desired_rotation_matrix_))
646 return fabs(absolute_x_axis_tolerance_ - o.absolute_x_axis_tolerance_) <= margin &&
647 fabs(absolute_y_axis_tolerance_ - o.absolute_y_axis_tolerance_) <= margin &&
648 fabs(absolute_z_axis_tolerance_ - o.absolute_z_axis_tolerance_) <= margin;
653 void OrientationConstraint::clear()
655 link_model_ =
nullptr;
656 desired_rotation_matrix_ = Eigen::Matrix3d::Identity();
657 desired_rotation_matrix_inv_ = Eigen::Matrix3d::Identity();
658 desired_rotation_frame_id_ =
"";
659 mobile_frame_ =
false;
660 absolute_z_axis_tolerance_ = absolute_y_axis_tolerance_ = absolute_x_axis_tolerance_ = 0.0;
663 bool OrientationConstraint::enabled()
const
673 Eigen::Isometry3d diff;
677 Eigen::Matrix3d tmp = state.
getFrameTransform(desired_rotation_frame_id_).linear() * desired_rotation_matrix_;
684 diff = Eigen::Isometry3d(desired_rotation_matrix_inv_ * state.
getGlobalLinkTransform(link_model_).linear());
688 std::tuple<Eigen::Vector3d, bool> euler_angles_error;
690 if (parameterization_type_ == moveit_msgs::OrientationConstraint::XYZ_EULER_ANGLES)
699 xyz_rotation = std::get<Eigen::Vector3d>(euler_angles_error);
700 if (!std::get<bool>(euler_angles_error))
702 if (
normalizeAbsoluteAngle(xyz_rotation(0)) > absolute_z_axis_tolerance_ + std::numeric_limits<double>::epsilon())
704 xyz_rotation(2) = xyz_rotation(0);
711 else if (parameterization_type_ == moveit_msgs::OrientationConstraint::ROTATION_VECTOR)
713 Eigen::AngleAxisd aa(diff.linear());
715 xyz_rotation = (desired_R_in_frame_id_ * (aa.axis() * aa.angle())).cwiseAbs();
721 "The parameterization type for the orientation constraints is invalid.");
724 bool result = xyz_rotation(2) < absolute_z_axis_tolerance_ + std::numeric_limits<double>::epsilon() &&
725 xyz_rotation(1) < absolute_y_axis_tolerance_ + std::numeric_limits<double>::epsilon() &&
726 xyz_rotation(0) < absolute_x_axis_tolerance_ + std::numeric_limits<double>::epsilon();
731 Eigen::Quaterniond q_des(desired_rotation_matrix_);
733 "Orientation constraint %s for link '%s'. Quaternion desired: %f %f %f %f, quaternion "
734 "actual: %f %f %f %f, error: x=%f, y=%f, z=%f, tolerance: x=%f, y=%f, z=%f",
735 result ?
"satisfied" :
"violated", link_model_->getName().c_str(), q_des.x(), q_des.y(), q_des.z(),
736 q_des.w(), q_act.x(), q_act.y(), q_act.z(), q_act.w(), xyz_rotation(0), xyz_rotation(1),
737 xyz_rotation(2), absolute_x_axis_tolerance_, absolute_y_axis_tolerance_, absolute_z_axis_tolerance_);
740 return ConstraintEvaluationResult(result, constraint_weight_ * (xyz_rotation(0) + xyz_rotation(1) + xyz_rotation(2)));
747 out <<
"Orientation constraint on link '" << link_model_->getName() <<
"'" << std::endl;
748 Eigen::Quaterniond q_des(desired_rotation_matrix_);
749 out <<
"Desired orientation:" << q_des.x() <<
"," << q_des.y() <<
"," << q_des.z() <<
"," << q_des.w() << std::endl;
752 out <<
"No constraint" << std::endl;
755 VisibilityConstraint::VisibilityConstraint(
const moveit::core::RobotModelConstPtr& model)
756 : KinematicConstraint(model), collision_env_(new
collision_detection::CollisionEnvFCL(model))
782 if (vc.target_radius <= std::numeric_limits<double>::epsilon())
784 "The radius of the target disc that must be visible should be strictly positive");
786 if (vc.cone_sides < 3)
789 "The number of sides for the visibility region must be 3 or more. "
790 "Assuming 3 sides instead of the specified %d",
799 double delta = 2.0 * boost::math::constants::pi<double>() / (double)
cone_sides_;
801 for (
unsigned int i = 0; i <
cone_sides_; ++i, a += delta)
841 if (vc.weight <= std::numeric_limits<double>::epsilon())
843 ROS_WARN_NAMED(
"kinematic_constraints",
"The weight of visibility constraint is near zero. Setting to 1.0.");
858 if (other.getType() !=
type_)
869 Eigen::Isometry3d diff =
sensor_pose_.inverse() * o.sensor_pose_;
870 if (diff.translation().norm() > margin)
872 if (!diff.linear().isIdentity(margin))
876 if (diff.translation().norm() > margin)
878 if (!diff.linear().isIdentity(margin))
894 const Eigen::Isometry3d& sp =
896 const Eigen::Isometry3d& tp =
901 std::unique_ptr<EigenSTL::vector_Vector3d> temp_points;
904 temp_points = std::make_unique<EigenSTL::vector_Vector3d>(
points_.size());
905 for (std::size_t i = 0; i <
points_.size(); ++i)
906 temp_points->at(i) = tp *
points_[i];
907 points = temp_points.get();
919 m->
vertices[0] = sp.translation().x();
920 m->
vertices[1] = sp.translation().y();
921 m->
vertices[2] = sp.translation().z();
924 m->
vertices[3] = tp.translation().x();
925 m->
vertices[4] = tp.translation().y();
926 m->
vertices[5] = tp.translation().z();
929 for (std::size_t i = 0; i < points->size(); ++i)
931 m->
vertices[i * 3 + 6] = points->at(i).x();
932 m->
vertices[i * 3 + 7] = points->at(i).y();
933 m->
vertices[i * 3 + 8] = points->at(i).z();
937 std::size_t p3 = points->size() * 3;
938 for (std::size_t i = 1; i < points->size(); ++i)
941 std::size_t i3 = (i - 1) * 3;
946 std::size_t i6 = p3 + i3;
953 m->
triangles[p3 - 3] = points->size() + 1;
957 m->
triangles[p3 - 3] = points->size() + 1;
965 visualization_msgs::MarkerArray& markers)
const
968 visualization_msgs::Marker mk;
973 mk.ns =
"constraints";
975 mk.action = visualization_msgs::Marker::ADD;
976 mk.pose.position.x = 0;
977 mk.pose.position.y = 0;
978 mk.pose.position.z = 0;
979 mk.pose.orientation.x = 0;
980 mk.pose.orientation.y = 0;
981 mk.pose.orientation.z = 0;
982 mk.pose.orientation.w = 1;
991 markers.markers.push_back(mk);
995 const Eigen::Isometry3d& sp =
998 const Eigen::Isometry3d& tp =
1001 visualization_msgs::Marker mka;
1002 mka.type = visualization_msgs::Marker::ARROW;
1003 mka.action = visualization_msgs::Marker::ADD;
1004 mka.color = mk.color;
1007 mka.header = mk.header;
1010 mka.lifetime = mk.lifetime;
1014 mka.points.resize(2);
1016 mka.points[0].x = tp.translation().x();
1017 mka.points[0].y = tp.translation().y();
1018 mka.points[0].z = tp.translation().z();
1019 mka.points[1].x =
d.x();
1020 mka.points[1].y =
d.y();
1021 mka.points[1].z =
d.z();
1022 markers.markers.push_back(mka);
1029 mka.points[0].x = sp.translation().x();
1030 mka.points[0].y = sp.translation().y();
1031 mka.points[0].z = sp.translation().z();
1032 mka.points[1].x =
d.x();
1033 mka.points[1].y =
d.y();
1034 mka.points[1].z =
d.z();
1036 markers.markers.push_back(mka);
1048 const Eigen::Isometry3d& sp =
1051 const Eigen::Isometry3d& tp =
1060 double dp = normal2.dot(normal1);
1061 double ang = acos(dp);
1065 ROS_INFO_NAMED(
"kinematic_constraints",
"Visibility constraint is violated because the sensor is looking at "
1073 "Visibility constraint is violated because the view angle is %lf "
1074 "(above the maximum allowed of %lf)",
1081 const Eigen::Vector3d& dir = (tp.translation() - sp.translation()).normalized();
1082 double dp = normal2.dot(dir);
1086 ROS_INFO_NAMED(
"kinematic_constraints",
"Visibility constraint is violated because the sensor is looking at "
1088 return ConstraintEvaluationResult(
false, 0.0);
1091 double ang = acos(dp);
1096 "Visibility constraint is violated because the range angle is %lf "
1097 "(above the maximum allowed of %lf)",
1099 return ConstraintEvaluationResult(
false, 0.0);
1106 return ConstraintEvaluationResult(
false, 0.0);
1123 std::stringstream ss;
1125 ROS_INFO_NAMED(
"kinematic_constraints",
"Visibility constraint %ssatisfied. Visibility cone approximation:\n %s",
1126 res.
collision ?
"not " :
"", ss.str().c_str());
1144 ROS_DEBUG_NAMED(
"kinematic_constraints",
"Accepted collision with either sensor or target");
1152 ROS_DEBUG_NAMED(
"kinematic_constraints",
"Accepted collision with either sensor or target");
1162 out <<
"Visibility constraint for sensor in frame '" <<
sensor_frame_id_ <<
"' using target in frame '"
1167 out <<
"No constraint" << std::endl;
1183 for (
const moveit_msgs::JointConstraint& joint_constraint : jc)
1185 JointConstraint* ev =
new JointConstraint(
robot_model_);
1186 bool u = ev->configure(joint_constraint);
1187 result = result && u;
1199 for (
const moveit_msgs::PositionConstraint& position_constraint : pc)
1201 PositionConstraint* ev =
new PositionConstraint(
robot_model_);
1202 bool u = ev->configure(position_constraint, tf);
1203 result = result && u;
1215 for (
const moveit_msgs::OrientationConstraint& orientation_constraint : oc)
1218 bool u = ev->
configure(orientation_constraint, tf);
1219 result = result && u;
1222 all_constraints_.orientation_constraints.push_back(orientation_constraint);
1231 for (
const moveit_msgs::VisibilityConstraint& visibility_constraint : vc)
1234 bool u = ev->
configure(visibility_constraint, tf);
1235 result = result && u;
1245 bool j =
add(c.joint_constraints);
1246 bool p =
add(c.position_constraints, tf);
1247 bool o =
add(c.orientation_constraints, tf);
1248 bool v =
add(c.visibility_constraints, tf);
1249 return j && p && o && v;
1259 res.satisfied =
false;
1266 std::vector<ConstraintEvaluationResult>& results,
1269 ConstraintEvaluationResult result(
true, 0.0);
1274 result.satisfied = result.satisfied && results[i].satisfied;
1275 result.distance += results[i].distance;
1285 kinematic_constraint->print(out);