43 #include <boost/math/constants/constants.hpp> 45 #include <boost/bind.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>();
62 : type_(UNKNOWN_CONSTRAINT), robot_model_(model), constraint_weight_(
std::numeric_limits<double>::
epsilon())
74 if (jc.tolerance_above < 0.0 || jc.tolerance_below < 0.0)
76 ROS_WARN_NAMED(
"kinematic_constraints",
"JointConstraint tolerance values must be positive.");
77 joint_model_ =
nullptr;
81 joint_variable_name_ = jc.joint_name;
82 local_variable_name_.clear();
84 joint_model_ =
robot_model_->getJointModel(joint_variable_name_);
87 std::size_t pos = jc.joint_name.find_last_of(
"/");
88 if (pos != std::string::npos)
90 joint_model_ =
robot_model_->getJointModel(jc.joint_name.substr(0, pos));
91 if (pos + 1 < jc.joint_name.length())
92 local_variable_name_ = jc.joint_name.substr(pos + 1);
95 joint_model_ =
robot_model_->getJointModel(jc.joint_name);
100 if (local_variable_name_.empty())
103 if (joint_model_->getVariableCount() == 0)
105 ROS_ERROR_NAMED(
"kinematic_constraints",
"Joint '%s' has no parameters to constrain", jc.joint_name.c_str());
106 joint_model_ =
nullptr;
108 else if (joint_model_->getVariableCount() > 1)
110 ROS_ERROR_NAMED(
"kinematic_constraints",
"Joint '%s' has more than one parameter to constrain. " 111 "This type of constraint is not supported.",
112 jc.joint_name.c_str());
113 joint_model_ =
nullptr;
119 const std::vector<std::string>& local_var_names = joint_model_->getLocalVariableNames();
120 for (std::size_t i = 0; i < local_var_names.size(); ++i)
121 if (local_var_names[i] == local_variable_name_)
128 ROS_ERROR_NAMED(
"kinematic_constraints",
"Local variable name '%s' is not known to joint '%s'",
129 local_variable_name_.c_str(), joint_model_->getName().c_str());
130 joint_model_ =
nullptr;
137 joint_is_continuous_ =
false;
138 joint_tolerance_above_ = jc.tolerance_above;
139 joint_tolerance_below_ = jc.tolerance_below;
140 joint_variable_index_ =
robot_model_->getVariableIndex(joint_variable_name_);
143 joint_is_continuous_ =
false;
148 joint_is_continuous_ =
true;
152 if (local_variable_name_ ==
"theta")
153 joint_is_continuous_ =
true;
156 if (joint_is_continuous_)
162 joint_position_ = jc.position;
165 if (bounds.
min_position_ > joint_position_ + joint_tolerance_above_)
168 joint_tolerance_above_ = std::numeric_limits<double>::epsilon();
169 ROS_WARN_NAMED(
"kinematic_constraints",
"Joint %s is constrained to be below the minimum bounds. " 170 "Assuming minimum bounds instead.",
171 jc.joint_name.c_str());
173 else if (bounds.
max_position_ < joint_position_ - joint_tolerance_below_)
176 joint_tolerance_below_ = std::numeric_limits<double>::epsilon();
177 ROS_WARN_NAMED(
"kinematic_constraints",
"Joint %s is constrained to be above the maximum bounds. " 178 "Assuming maximum bounds instead.",
179 jc.joint_name.c_str());
183 if (jc.weight <= std::numeric_limits<double>::epsilon())
186 "The weight on constraint for joint '%s' is very near zero. Setting to 1.0.",
187 jc.joint_name.c_str());
193 return joint_model_ !=
nullptr;
217 if (joint_is_continuous_)
221 if (dif > boost::math::constants::pi<double>())
222 dif = 2.0 * boost::math::constants::pi<double>() - dif;
223 else if (dif < -boost::math::constants::pi<double>())
224 dif += 2.0 * boost::math::constants::pi<double>();
227 dif = current_joint_position - joint_position_;
230 bool result = dif <= (joint_tolerance_above_ + 2.0 * std::numeric_limits<double>::epsilon()) &&
231 dif >= (-joint_tolerance_below_ - 2.0 * std::numeric_limits<double>::epsilon());
233 ROS_INFO_NAMED(
"kinematic_constraints",
"Constraint %s:: Joint name: '%s', actual value: %f, desired value: %f, " 234 "tolerance_above: %f, tolerance_below: %f",
235 result ?
"satisfied" :
"violated", joint_variable_name_.c_str(), current_joint_position,
236 joint_position_, joint_tolerance_above_, joint_tolerance_below_);
247 joint_model_ =
nullptr;
248 joint_variable_index_ = -1;
249 joint_is_continuous_ =
false;
250 local_variable_name_ =
"";
251 joint_variable_name_ =
"";
252 joint_position_ = joint_tolerance_below_ = joint_tolerance_above_ = 0.0;
259 out <<
"Joint constraint for joint " << joint_variable_name_ <<
": " << std::endl;
261 out << joint_position_ <<
"; ";
262 out <<
" tolerance below = ";
263 out << joint_tolerance_below_ <<
"; ";
264 out <<
" tolerance above = ";
265 out << joint_tolerance_above_ <<
"; ";
269 out <<
"No constraint" << std::endl;
278 if (link_model_ ==
nullptr)
281 "Position constraint link model %s not found in kinematic model. Constraint invalid.",
282 pc.link_name.c_str());
286 if (pc.header.frame_id.empty())
288 ROS_WARN_NAMED(
"kinematic_constraints",
"No frame specified for position constraint on link '%s'!",
289 pc.link_name.c_str());
293 offset_ = Eigen::Vector3d(pc.target_point_offset.x, pc.target_point_offset.y, pc.target_point_offset.z);
294 has_offset_ = offset_.squaredNorm() > std::numeric_limits<double>::epsilon();
299 mobile_frame_ =
false;
303 constraint_frame_id_ = pc.header.frame_id;
304 mobile_frame_ =
true;
308 for (std::size_t i = 0; i < pc.constraint_region.primitives.size(); ++i)
313 if (pc.constraint_region.primitive_poses.size() <= i)
315 ROS_WARN_NAMED(
"kinematic_constraints",
"Constraint region message does not contain enough primitive poses");
321 constraint_region_pose_.push_back(t);
323 constraint_region_.back()->setPose(constraint_region_pose_.back());
326 tf.
transformPose(pc.header.frame_id, constraint_region_pose_.back(), constraint_region_pose_.back());
327 constraint_region_.back()->setPose(constraint_region_pose_.back());
331 ROS_WARN_NAMED(
"kinematic_constraints",
"Could not construct primitive shape %zu", i);
335 for (std::size_t i = 0; i < pc.constraint_region.meshes.size(); ++i)
340 if (pc.constraint_region.mesh_poses.size() <= i)
342 ROS_WARN_NAMED(
"kinematic_constraints",
"Constraint region message does not contain enough primitive poses");
348 constraint_region_pose_.push_back(t);
350 constraint_region_.back()->setPose(constraint_region_pose_.back());
353 tf.
transformPose(pc.header.frame_id, constraint_region_pose_.back(), constraint_region_pose_.back());
354 constraint_region_.back()->setPose(constraint_region_pose_.back());
359 ROS_WARN_NAMED(
"kinematic_constraints",
"Could not construct mesh shape %zu", i);
363 if (pc.weight <= std::numeric_limits<double>::epsilon())
366 "The weight on position constraint for link '%s' is near zero. Setting to 1.0.",
367 pc.link_name.c_str());
373 return !constraint_region_.empty();
384 if ((offset_ - o.
offset_).norm() > margin)
386 std::vector<bool> other_region_matches_this(constraint_region_.size(),
false);
387 for (std::size_t i = 0; i < constraint_region_.size(); ++i)
389 bool some_match =
false;
394 if (diff.translation().norm() < margin && diff.linear().isIdentity(margin) &&
396 fabs(constraint_region_[i]->computeVolume() - o.
constraint_region_[j]->computeVolume()) < margin)
400 other_region_matches_this[j] =
true;
407 if (!other_region_matches_this[i])
416 const Eigen::Vector3d& desired,
417 const std::string& name,
double weight,
418 bool result,
bool verbose)
420 double dx = desired.x() - pt.x();
421 double dy = desired.y() - pt.y();
422 double dz = desired.z() - pt.z();
426 "kinematic_constraints",
"Position constraint %s on link '%s'. Desired: %f, %f, %f, current: %f, %f, %f",
427 result ?
"satisfied" :
"violated", name.c_str(), desired.x(), desired.y(), desired.z(), pt.x(), pt.y(), pt.z());
428 ROS_INFO_NAMED(
"kinematic_constraints",
"Differences %g %g %g", dx, dy, dz);
435 if (!link_model_ || constraint_region_.empty())
441 for (std::size_t i = 0; i < constraint_region_.size(); ++i)
443 Eigen::Affine3d tmp = state.
getFrameTransform(constraint_frame_id_) * constraint_region_pose_[i];
444 bool result = constraint_region_[i]->cloneAt(tmp)->containsPoint(pt, verbose);
445 if (result || (i + 1 == constraint_region_pose_.size()))
455 for (std::size_t i = 0; i < constraint_region_.size(); ++i)
457 bool result = constraint_region_[i]->containsPoint(pt,
true);
458 if (result || (i + 1 == constraint_region_.size()))
472 out <<
"Position constraint on link '" << link_model_->getName() <<
"'" << std::endl;
474 out <<
"No constraint" << std::endl;
479 offset_ = Eigen::Vector3d(0.0, 0.0, 0.0);
481 constraint_region_.clear();
482 constraint_region_pose_.clear();
483 mobile_frame_ =
false;
484 constraint_frame_id_ =
"";
485 link_model_ =
nullptr;
490 return link_model_ && !constraint_region_.empty();
501 ROS_WARN_NAMED(
"kinematic_constraints",
"Could not find link model for link name %s", oc.link_name.c_str());
504 Eigen::Quaterniond q;
506 if (fabs(q.norm() - 1.0) > 1e-3)
508 ROS_WARN_NAMED(
"kinematic_constraints",
"Orientation constraint for link '%s' is probably incorrect: %f, %f, %f, " 509 "%f. Assuming identity instead.",
510 oc.link_name.c_str(), oc.orientation.x, oc.orientation.y, oc.orientation.z, oc.orientation.w);
511 q = Eigen::Quaterniond(1.0, 0.0, 0.0, 0.0);
514 if (oc.header.frame_id.empty())
515 ROS_WARN_NAMED(
"kinematic_constraints",
"No frame specified for position constraint on link '%s'!",
516 oc.link_name.c_str());
522 desired_rotation_matrix_ = Eigen::Matrix3d(q);
523 desired_rotation_matrix_inv_ = desired_rotation_matrix_.transpose();
524 mobile_frame_ =
false;
528 desired_rotation_frame_id_ = oc.header.frame_id;
529 desired_rotation_matrix_ = Eigen::Matrix3d(q);
530 mobile_frame_ =
true;
532 std::stringstream matrix_str;
533 matrix_str << desired_rotation_matrix_;
534 ROS_DEBUG_NAMED(
"kinematic_constraints",
"The desired rotation matrix for link '%s' in frame %s is:\n%s",
535 oc.link_name.c_str(), desired_rotation_frame_id_.c_str(), matrix_str.str().c_str());
537 if (oc.weight <= std::numeric_limits<double>::epsilon())
540 "The weight on position constraint for link '%s' is near zero. Setting to 1.0.",
541 oc.link_name.c_str());
546 absolute_x_axis_tolerance_ = fabs(oc.absolute_x_axis_tolerance);
547 if (absolute_x_axis_tolerance_ < std::numeric_limits<double>::epsilon())
548 ROS_WARN_NAMED(
"kinematic_constraints",
"Near-zero value for absolute_x_axis_tolerance");
549 absolute_y_axis_tolerance_ = fabs(oc.absolute_y_axis_tolerance);
550 if (absolute_y_axis_tolerance_ < std::numeric_limits<double>::epsilon())
551 ROS_WARN_NAMED(
"kinematic_constraints",
"Near-zero value for absolute_y_axis_tolerance");
552 absolute_z_axis_tolerance_ = fabs(oc.absolute_z_axis_tolerance);
553 if (absolute_z_axis_tolerance_ < std::numeric_limits<double>::epsilon())
554 ROS_WARN_NAMED(
"kinematic_constraints",
"Near-zero value for absolute_z_axis_tolerance");
556 return link_model_ !=
nullptr;
579 link_model_ =
nullptr;
580 desired_rotation_matrix_ = Eigen::Matrix3d::Identity();
581 desired_rotation_matrix_inv_ = Eigen::Matrix3d::Identity();
582 desired_rotation_frame_id_ =
"";
583 mobile_frame_ =
false;
584 absolute_z_axis_tolerance_ = absolute_y_axis_tolerance_ = absolute_x_axis_tolerance_ = 0.0;
600 Eigen::Matrix3d tmp = state.
getFrameTransform(desired_rotation_frame_id_).linear() * desired_rotation_matrix_;
602 xyz =
diff.linear().eulerAngles(0, 1, 2);
608 xyz =
diff.linear().eulerAngles(0, 1, 2);
611 xyz(0) = std::min(fabs(xyz(0)), boost::math::constants::pi<double>() - fabs(xyz(0)));
612 xyz(1) = std::min(fabs(xyz(1)), boost::math::constants::pi<double>() - fabs(xyz(1)));
613 xyz(2) = std::min(fabs(xyz(2)), boost::math::constants::pi<double>() - fabs(xyz(2)));
614 bool result = xyz(2) < absolute_z_axis_tolerance_ + std::numeric_limits<double>::epsilon() &&
615 xyz(1) < absolute_y_axis_tolerance_ + std::numeric_limits<double>::epsilon() &&
616 xyz(0) < absolute_x_axis_tolerance_ + std::numeric_limits<double>::epsilon();
621 Eigen::Quaterniond q_des(desired_rotation_matrix_);
623 "Orientation constraint %s for link '%s'. Quaternion desired: %f %f %f %f, quaternion " 624 "actual: %f %f %f %f, error: x=%f, y=%f, z=%f, tolerance: x=%f, y=%f, z=%f",
625 result ?
"satisfied" :
"violated", link_model_->getName().c_str(), q_des.x(), q_des.y(), q_des.z(),
626 q_des.w(), q_act.x(), q_act.y(), q_act.z(), q_act.w(), xyz(0), xyz(1), xyz(2),
627 absolute_x_axis_tolerance_, absolute_y_axis_tolerance_, absolute_z_axis_tolerance_);
637 out <<
"Orientation constraint on link '" << link_model_->getName() <<
"'" << std::endl;
638 Eigen::Quaterniond q_des(desired_rotation_matrix_);
639 out <<
"Desired orientation:" << q_des.x() <<
"," << q_des.y() <<
"," << q_des.z() <<
"," << q_des.w() << std::endl;
642 out <<
"No constraint" << std::endl;
672 if (vc.target_radius <= std::numeric_limits<double>::epsilon())
674 "The radius of the target disc that must be visible should be strictly positive");
676 if (vc.cone_sides < 3)
678 ROS_WARN_NAMED(
"kinematic_constraints",
"The number of sides for the visibility region must be 3 or more. " 679 "Assuming 3 sides instead of the specified %d",
688 double delta = 2.0 * boost::math::constants::pi<double>() / (
double)
cone_sides_;
690 for (
unsigned int i = 0; i <
cone_sides_; ++i, a += delta)
694 points_.push_back(Eigen::Vector3d(x, y, 0.0));
705 for (std::size_t i = 0; i <
points_.size(); ++i)
728 if (vc.weight <= std::numeric_limits<double>::epsilon())
730 ROS_WARN_NAMED(
"kinematic_constraints",
"The weight of visibility constraint is near zero. Setting to 1.0.");
756 if (diff.translation().norm() > margin)
758 if (!diff.linear().isIdentity(margin))
761 if (diff.translation().norm() > margin)
763 if (!diff.linear().isIdentity(margin))
779 const Eigen::Affine3d& sp =
781 const Eigen::Affine3d& tp =
786 std::unique_ptr<EigenSTL::vector_Vector3d> tempPoints;
790 for (std::size_t i = 0; i <
points_.size(); ++i)
791 tempPoints->at(i) = tp *
points_[i];
792 points = tempPoints.get();
804 m->
vertices[0] = sp.translation().x();
805 m->
vertices[1] = sp.translation().y();
806 m->
vertices[2] = sp.translation().z();
809 m->
vertices[3] = tp.translation().x();
810 m->
vertices[4] = tp.translation().y();
811 m->
vertices[5] = tp.translation().z();
814 for (std::size_t i = 0; i < points->size(); ++i)
816 m->
vertices[i * 3 + 6] = points->at(i).x();
817 m->
vertices[i * 3 + 7] = points->at(i).y();
818 m->
vertices[i * 3 + 8] = points->at(i).z();
822 std::size_t p3 = points->size() * 3;
823 for (std::size_t i = 1; i < points->size(); ++i)
826 std::size_t i3 = (i - 1) * 3;
831 std::size_t i6 = p3 + i3;
838 m->
triangles[p3 - 3] = points->size() + 1;
842 m->
triangles[p3 - 3] = points->size() + 1;
850 visualization_msgs::MarkerArray& markers)
const 853 visualization_msgs::Marker mk;
858 mk.ns =
"constraints";
860 mk.action = visualization_msgs::Marker::ADD;
861 mk.pose.position.x = 0;
862 mk.pose.position.y = 0;
863 mk.pose.position.z = 0;
864 mk.pose.orientation.x = 0;
865 mk.pose.orientation.y = 0;
866 mk.pose.orientation.z = 0;
867 mk.pose.orientation.w = 1;
876 markers.markers.push_back(mk);
878 const Eigen::Affine3d& sp =
880 const Eigen::Affine3d& tp =
883 visualization_msgs::Marker mka;
884 mka.type = visualization_msgs::Marker::ARROW;
885 mka.action = visualization_msgs::Marker::ADD;
886 mka.color = mk.color;
889 mka.header = mk.header;
892 mka.lifetime = mk.lifetime;
896 mka.points.resize(2);
897 Eigen::Vector3d
d = tp.translation() + tp.linear().col(2) * 0.5;
898 mka.points[0].x = tp.translation().x();
899 mka.points[0].y = tp.translation().y();
900 mka.points[0].z = tp.translation().z();
901 mka.points[1].x = d.x();
902 mka.points[1].y = d.y();
903 mka.points[1].z = d.z();
904 markers.markers.push_back(mka);
911 mka.points[0].x = sp.translation().x();
912 mka.points[0].y = sp.translation().y();
913 mka.points[0].z = sp.translation().z();
914 mka.points[1].x = d.x();
915 mka.points[1].y = d.y();
916 mka.points[1].z = d.z();
918 markers.markers.push_back(mka);
928 const Eigen::Affine3d& sp =
930 const Eigen::Affine3d& tp =
938 const Eigen::Vector3d& normal1 = tp.linear().col(2) * -1.0;
939 double dp = normal2.dot(normal1);
940 double ang =
acos(dp);
944 ROS_INFO_NAMED(
"kinematic_constraints",
"Visibility constraint is violated because the sensor is looking at " 951 ROS_INFO_NAMED(
"kinematic_constraints",
"Visibility constraint is violated because the view angle is %lf " 952 "(above the maximum allowed of %lf)",
959 const Eigen::Vector3d& dir = (tp.translation() - sp.translation()).normalized();
960 double dp = normal2.dot(dir);
964 ROS_INFO_NAMED(
"kinematic_constraints",
"Visibility constraint is violated because the sensor is looking at " 969 double ang =
acos(dp);
973 ROS_INFO_NAMED(
"kinematic_constraints",
"Visibility constraint is violated because the range angle is %lf " 974 "(above the maximum allowed of %lf)",
1001 std::stringstream ss;
1003 ROS_INFO_NAMED(
"kinematic_constraints",
"Visibility constraint %ssatisfied. Visibility cone approximation:\n %s",
1004 res.
collision ?
"not " :
"", ss.str().c_str());
1020 ROS_DEBUG_NAMED(
"kinematic_constraints",
"Accepted collision with either sensor or target");
1028 ROS_DEBUG_NAMED(
"kinematic_constraints",
"Accepted collision with either sensor or target");
1038 out <<
"Visibility constraint for sensor in frame '" <<
sensor_frame_id_ <<
"' using target in frame '" 1043 out <<
"No constraint" << std::endl;
1048 all_constraints_ = moveit_msgs::Constraints();
1049 kinematic_constraints_.clear();
1050 joint_constraints_.clear();
1051 position_constraints_.clear();
1052 orientation_constraints_.clear();
1053 visibility_constraints_.clear();
1059 for (
unsigned int i = 0; i < jc.size(); ++i)
1063 result = result && u;
1064 kinematic_constraints_.push_back(KinematicConstraintPtr(ev));
1065 joint_constraints_.push_back(jc[i]);
1066 all_constraints_.joint_constraints.push_back(jc[i]);
1075 for (
unsigned int i = 0; i < pc.size(); ++i)
1079 result = result && u;
1080 kinematic_constraints_.push_back(KinematicConstraintPtr(ev));
1081 position_constraints_.push_back(pc[i]);
1082 all_constraints_.position_constraints.push_back(pc[i]);
1091 for (
unsigned int i = 0; i < oc.size(); ++i)
1095 result = result && u;
1096 kinematic_constraints_.push_back(KinematicConstraintPtr(ev));
1097 orientation_constraints_.push_back(oc[i]);
1098 all_constraints_.orientation_constraints.push_back(oc[i]);
1107 for (
unsigned int i = 0; i < vc.size(); ++i)
1111 result = result && u;
1112 kinematic_constraints_.push_back(KinematicConstraintPtr(ev));
1113 visibility_constraints_.push_back(vc[i]);
1114 all_constraints_.visibility_constraints.push_back(vc[i]);
1121 bool j = add(c.joint_constraints);
1122 bool p = add(c.position_constraints, tf);
1123 bool o = add(c.orientation_constraints, tf);
1124 bool v = add(c.visibility_constraints, tf);
1125 return j && p && o && v;
1131 for (
unsigned int i = 0; i < kinematic_constraints_.size(); ++i)
1142 std::vector<ConstraintEvaluationResult>& results,
1146 results.resize(kinematic_constraints_.size());
1147 for (std::size_t i = 0; i < kinematic_constraints_.size(); ++i)
1149 results[i] = kinematic_constraints_[i]->decide(state, verbose);
1151 result.
distance += results[i].distance;
1159 out << kinematic_constraints_.size() <<
" kinematic constraints" << std::endl;
1160 for (
unsigned int i = 0; i < kinematic_constraints_.size(); ++i)
1161 kinematic_constraints_[i]->
print(out);
1167 for (
unsigned int i = 0; i < kinematic_constraints_.size(); ++i)
1179 for (
unsigned int j = 0; !found && j < kinematic_constraints_.size(); ++j)
collision_detection::CollisionRobotPtr collision_robot_
A copy of the collision robot maintained for collision checking the cone against robot links...
Representation of a collision checking request.
bool decideContact(const collision_detection::Contact &contact) const
Function that gets passed into collision checking to allow some collisions.
bool configure(const moveit_msgs::OrientationConstraint &oc, const robot_state::Transforms &tf)
Configure the constraint based on a moveit_msgs::OrientationConstraint.
const WorldPtr & getWorld()
#define ROS_INFO_NAMED(name,...)
double absolute_z_axis_tolerance_
Storage for the tolerances.
Class for constraints on the orientation of a link.
ConstraintType type_
The type of the constraint.
int sensor_view_direction_
Storage for the sensor view direction.
Class for constraints on the visibility relationship between a sensor and a target.
#define ROS_WARN_NAMED(name,...)
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
bool mobile_sensor_frame_
True if the sensor is a non-fixed frame relative to the transform frame.
const Eigen::Affine3d & getGlobalLinkTransform(const std::string &link_name)
bool configure(const moveit_msgs::PositionConstraint &pc, const robot_state::Transforms &tf)
Configure the constraint based on a moveit_msgs::PositionConstraint.
EigenSTL::vector_Vector3d points_
A set of points along the base of the circle.
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
virtual void clear()=0
Clear the stored constraint.
A body attached to a robot link.
Class for handling single DOF joint constraints.
std::shared_ptr< Body > BodyPtr
ContactMap contacts
A map returning the pairs of ids of the bodies in contact, plus information about the contacts themse...
double max_view_angle_
Storage for the max view angle.
Eigen::Affine3d target_pose_
The target pose transformed into the transform frame.
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
double joint_tolerance_below_
Position and tolerance values.
A class that contains many different constraints, and can check RobotState *versus the full set...
double joint_tolerance_above_
const Eigen::Affine3d & getFrameTransform(const std::string &id)
Get the transformation matrix from the model frame to the frame identified by id. ...
virtual ConstraintEvaluationResult decide(const robot_state::RobotState &state, bool verbose=false) const
Decide whether the constraint is satisfied in the indicated state.
Representation of a collision checking result.
virtual void print(std::ostream &out=std::cout) const
bool configure(const moveit_msgs::VisibilityConstraint &vc, const robot_state::Transforms &tf)
Configure the constraint based on a moveit_msgs::VisibilityConstraint.
virtual bool enabled() const
This function returns true if this constraint is configured and able to decide whether states do meet...
Representation and evaluation of kinematic constraints.
virtual void print(std::ostream &out=std::cout) const
Print the constraint data.
void print(std::ostream &out=std::cout) const
Print the constraint data.
Generic interface to collision detection.
bool equal(const KinematicConstraintSet &other, double margin) const
Whether or not another KinematicConstraintSet is equal to this one.
double distance
The distance evaluation from the constraint or constraints.
bool isContinuous() const
Check if this joint wraps around.
double target_radius_
Storage for the target radius.
virtual void print(std::ostream &out=std::cout) const
Print the constraint data.
const robot_model::LinkModel * link_model_
The target link model.
double absolute_x_axis_tolerance_
bool collision
True if collision was found, false otherwise.
Eigen::Matrix3d desired_rotation_matrix_
The desired rotation matrix in the tf frame.
std::string sensor_frame_id_
The sensor frame id.
bool add(const moveit_msgs::Constraints &c, const robot_state::Transforms &tf)
Add all known constraints.
KinematicConstraint(const robot_model::RobotModelConstPtr &model)
Constructor.
bool satisfied
Whether or not the constraint or constraints were satisfied.
#define ROS_DEBUG_NAMED(name,...)
virtual bool equal(const KinematicConstraint &other, double margin) const
Check if two joint constraints are the same.
unsigned int vertex_count
std::size_t max_contacts
Overall maximum number of contacts to compute.
bool verbose
Flag indicating whether information about detected collisions should be reported. ...
Eigen::Affine3d sensor_pose_
The sensor pose transformed into the transform frame.
std::string desired_rotation_frame_id_
The target frame of the transform tree.
std::string local_variable_name_
The local variable name for a multi DOF joint, if any.
std::vector< bodies::BodyPtr > constraint_region_
The constraint region vector.
unsigned int triangle_count
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
void getMarkers(const robot_state::RobotState &state, visualization_msgs::MarkerArray &markers) const
Adds markers associated with the visibility cone, sensor and target to the visualization array...
bool mobile_target_frame_
True if the target is a non-fixed frame relative to the transform frame.
Body * createBodyFromShape(const shapes::Shape *shape)
virtual ConstraintEvaluationResult decide(const robot_state::RobotState &state, bool verbose=false) const
Decide whether the constraint is satisfied in the indicated state.
const robot_model::LinkModel * link_model_
The link model constraint subject.
virtual void print(std::ostream &out=std::cout) const
Print the constraint data.
virtual void clear()
Clear the stored constraint.
robot_model::RobotModelConstPtr robot_model_
The kinematic model associated with this constraint.
std::string constraint_frame_id_
The constraint frame id.
Eigen::Vector3d offset_
The target offset.
virtual bool equal(const KinematicConstraint &other, double margin) const
Check if two orientation constraints are the same.
Base class for representing a kinematic constraint.
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
bool contacts
If true, compute contacts.
EigenSTL::vector_Affine3d constraint_region_pose_
The constraint region pose vector.
VisibilityConstraint(const robot_model::RobotModelConstPtr &model)
Constructor.
virtual bool equal(const KinematicConstraint &other, double margin) const
Check if two constraints are the same. For position constraints this means that:
bool constructMarkerFromShape(const Shape *shape, visualization_msgs::Marker &mk, bool use_mesh_triangle_list=false)
virtual bool enabled() const =0
This function returns true if this constraint is configured and able to decide whether states do meet...
virtual void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const
Check whether the robot model is in collision with the world. Any collisions between a robot link and...
virtual ~KinematicConstraint()
Shape * constructShapeFromMsg(const shape_msgs::SolidPrimitive &shape_msg)
Struct for containing the results of constraint evaluation.
Class for constraints on the XYZ position of a link.
std::string target_frame_id_
The target frame id.
void setDefaultEntry(const std::string &name, bool allowed)
Set the default value for entries that include name. If such a default value is set, queries to getAllowedCollision() that include name will return this value instead, even if a pair that includes name was previously specified with setEntry().
virtual void clear()
Clear the stored constraint.
unsigned int cone_sides_
Storage for the cone sides.
A body in the environment.
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
virtual bool enabled() const
This function returns true if this constraint is configured and able to decide whether states do meet...
double max_range_angle_
Storage for the max range angle.
shapes::Mesh * getVisibilityCone(const robot_state::RobotState &state) const
Gets a trimesh shape representing the visibility cone.
std::vector< KinematicConstraintPtr > kinematic_constraints_
Shared pointers to all the member constraints.
virtual bool equal(const KinematicConstraint &other, double margin) const
Check if two constraints are the same.
void quaternionMsgToEigen(const geometry_msgs::Quaternion &m, Eigen::Quaterniond &e)
#define ROS_ERROR_NAMED(name,...)
const robot_model::JointModel * joint_model_
The joint from the kinematic model for this constraint.
virtual void print(std::ostream &out=std::cout) const
Print the constraint data.
Representation of a robot's state. This includes position, velocity, acceleration and effort...
double getVariablePosition(const std::string &variable) const
Get the position of a particular variable. An exception is thrown if the variable is not known...
static ConstraintEvaluationResult finishPositionConstraintDecision(const Eigen::Vector3d &pt, const Eigen::Vector3d &desired, const std::string &name, double weight, bool result, bool verbose)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
virtual bool enabled() const
This function returns true if this constraint is configured and able to decide whether states do meet...
virtual void clear()
Clear the stored constraint.
void clear()
Clear the stored constraints.
double constraint_weight_
The weight of a constraint is a multiplicative factor associated to the distance computed by the deci...
virtual ConstraintEvaluationResult decide(const robot_state::RobotState &state, bool verbose=false) const
Decide whether the constraint is satisfied in the indicated state.
ConstraintType getType() const
Get the type of constraint.
static double normalizeAngle(double angle)
double absolute_y_axis_tolerance_
virtual bool enabled() const
This function returns true if this constraint is configured and able to decide whether states do meet...
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
bool configure(const moveit_msgs::JointConstraint &jc)
Configure the constraint based on a moveit_msgs::JointConstraint.
virtual void clear()
Clear the stored constraint.
ConstraintEvaluationResult decide(const robot_state::RobotState &state, bool verbose=false) const
Determines whether all constraints are satisfied by state, returning a single evaluation result...
virtual ConstraintEvaluationResult decide(const robot_state::RobotState &state, bool verbose=false) const
Decide whether the constraint is satisfied in the indicated state.
std::shared_ptr< const Shape > ShapeConstPtr