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>
53 #include <rclcpp/clock.hpp>
54 #include <rclcpp/duration.hpp>
59 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_kinematic_constraints.kinematic_constraints");
61 static double normalizeAngle(
double angle)
63 double v = fmod(angle, 2.0 * M_PI);
73 static double normalizeAbsoluteAngle(
const double angle)
75 const double normalized_angle = std::fmod(std::abs(angle), 2 * M_PI);
76 return std::min(2 * M_PI - normalized_angle, normalized_angle);
86 template <
typename Derived>
87 std::tuple<Eigen::Matrix<typename Eigen::MatrixBase<Derived>::Scalar, 3, 1>,
bool>
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;
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);
102 if (rsum > 4 * Eigen::NumTraits<Scalar>::epsilon())
104 res[0] = atan2(-R(j, k), R(k, k));
105 res[2] = atan2(-R(i, j), R(i, i));
106 return { res,
true };
108 else if (R(i, k) > 0)
110 const Scalar spos = R(j, i) + R(k, j);
111 const Scalar cpos = R(j, j) - R(k, i);
112 res[0] = atan2(spos, cpos);
114 return { res,
false };
116 const Scalar sneg = R(k, j) - R(j, i);
117 const Scalar cneg = R(j, j) + R(k, i);
118 res[0] = atan2(sneg, cneg);
120 return { res,
false };
124 : type_(UNKNOWN_CONSTRAINT), robot_model_(model), constraint_weight_(std::numeric_limits<double>::epsilon())
136 if (jc.tolerance_above < 0.0 || jc.tolerance_below < 0.0)
138 RCLCPP_WARN(LOGGER,
"JointConstraint tolerance values must be positive.");
149 std::size_t pos = jc.joint_name.find_last_of(
'/');
150 if (pos != std::string::npos)
153 if (pos + 1 < jc.joint_name.length())
167 RCLCPP_ERROR(LOGGER,
"Joint '%s' has no parameters to constrain", jc.joint_name.c_str());
173 "Joint '%s' has more than one parameter to constrain. "
174 "This type of constraint is not supported.",
175 jc.joint_name.c_str());
183 for (std::size_t i = 0; i < local_var_names.size(); ++i)
191 RCLCPP_ERROR(LOGGER,
"Local variable name '%s' is not known to joint '%s'",
local_variable_name_.c_str(),
234 "Joint %s is constrained to be below the minimum bounds. "
235 "Assuming minimum bounds instead.",
236 jc.joint_name.c_str());
243 "Joint %s is constrained to be above the maximum bounds. "
244 "Assuming maximum bounds instead.",
245 jc.joint_name.c_str());
249 if (jc.weight <= std::numeric_limits<double>::epsilon())
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());
287 dif = 2.0 * M_PI - dif;
288 else if (dif < -M_PI)
299 "Constraint %s:: Joint name: '%s', actual value: %f, desired value: %f, "
300 "tolerance_above: %f, tolerance_below: %f",
328 out <<
" tolerance below = ";
330 out <<
" tolerance above = ";
335 out <<
"No constraint" <<
'\n';
346 RCLCPP_WARN(LOGGER,
"Position constraint link model %s not found in kinematic model. Constraint invalid.",
347 pc.link_name.c_str());
351 if (pc.header.frame_id.empty())
353 RCLCPP_WARN(LOGGER,
"No frame specified for position constraint on link '%s'!", pc.link_name.c_str());
372 for (std::size_t i = 0; i < pc.constraint_region.primitives.size(); ++i)
374 std::unique_ptr<shapes::Shape> shape(shapes::constructShapeFromMsg(pc.constraint_region.primitives[i]));
377 if (pc.constraint_region.primitive_poses.size() <= i)
379 RCLCPP_WARN(LOGGER,
"Constraint region message does not contain enough primitive poses");
383 tf2::fromMsg(pc.constraint_region.primitive_poses[i], t);
389 const bodies::BodyPtr body(bodies::createEmptyBodyFromShapeType(shape->type));
390 body->setDimensionsDirty(shape.get());
392 body->updateInternalData();
396 RCLCPP_WARN(LOGGER,
"Could not construct primitive shape %zu", i);
400 for (std::size_t i = 0; i < pc.constraint_region.meshes.size(); ++i)
402 std::unique_ptr<shapes::Shape> shape(shapes::constructShapeFromMsg(pc.constraint_region.meshes[i]));
405 if (pc.constraint_region.mesh_poses.size() <= i)
407 RCLCPP_WARN(LOGGER,
"Constraint region message does not contain enough primitive poses");
411 tf2::fromMsg(pc.constraint_region.mesh_poses[i], t);
416 const bodies::BodyPtr body(bodies::createEmptyBodyFromShapeType(shape->type));
417 body->setDimensionsDirty(shape.get());
419 body->updateInternalData();
424 RCLCPP_WARN(LOGGER,
"Could not construct mesh shape %zu", i);
428 if (pc.weight <= std::numeric_limits<double>::epsilon())
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());
453 bool some_match =
false;
459 if (diff.translation().norm() < margin && diff.linear().isIdentity(margin) &&
465 other_region_matches_this[j] =
true;
472 if (!other_region_matches_this[i])
482 const std::string&
name,
double weight,
483 bool result,
bool verbose)
485 double dx = desired.x() - pt.x();
486 double dy = desired.y() - pt.y();
487 double dz = desired.z() - pt.z();
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(),
493 RCLCPP_INFO(LOGGER,
"Differences %g %g %g", dx, dy, dz);
495 return ConstraintEvaluationResult(result, weight * sqrt(dx * dx + dy * dy + dz * dz));
524 return finishPositionConstraintDecision(pt,
constraint_region_[i]->getPose().translation(),
539 out <<
"No constraint" <<
'\n';
567 RCLCPP_WARN(LOGGER,
"Could not find link model for link name %s", oc.link_name.c_str());
570 Eigen::Quaterniond q;
571 tf2::fromMsg(oc.orientation, q);
572 if (fabs(q.norm() - 1.0) > 1e-3)
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);
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());
598 std::stringstream matrix_str;
600 RCLCPP_DEBUG(LOGGER,
"The desired rotation matrix for link '%s' in frame %s is:\n%s", oc.link_name.c_str(),
603 if (oc.weight <= std::numeric_limits<double>::epsilon())
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());
620 "Unknown parameterization for orientation constraint tolerance, using default (XYZ_EULER_ANGLES).");
626 RCLCPP_WARN(LOGGER,
"Near-zero value for absolute_x_axis_tolerance");
629 RCLCPP_WARN(LOGGER,
"Near-zero value for absolute_y_axis_tolerance");
632 RCLCPP_WARN(LOGGER,
"Near-zero value for absolute_z_axis_tolerance");
675 Eigen::Isometry3d diff;
690 std::tuple<Eigen::Vector3d, bool> euler_angles_error;
701 xyz_rotation = std::get<Eigen::Vector3d>(euler_angles_error);
702 if (!std::get<bool>(euler_angles_error))
706 xyz_rotation(2) = xyz_rotation(0);
711 xyz_rotation = xyz_rotation.unaryExpr(&normalizeAbsoluteAngle);
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));
724 RCLCPP_ERROR(LOGGER,
"The parameterization type for the orientation constraints is invalid.");
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),
752 out <<
"Desired orientation:" << q_des.x() <<
"," << q_des.y() <<
"," << q_des.z() <<
"," << q_des.w() <<
'\n';
755 out <<
"No constraint" <<
'\n';
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");
789 if (vc.cone_sides < 3)
792 "The number of sides for the visibility region must be 3 or more. "
793 "Assuming 3 sides instead of the specified %d",
804 for (
unsigned int i = 0; i <
cone_sides_; ++i,
a += delta)
844 if (vc.weight <= std::numeric_limits<double>::epsilon())
846 RCLCPP_WARN(LOGGER,
"The weight of visibility constraint is near zero. Setting to 1.0.");
873 if (diff.translation().norm() > margin)
875 if (!diff.linear().isIdentity(margin))
879 if (diff.translation().norm() > margin)
881 if (!diff.linear().isIdentity(margin))
897 const Eigen::Isometry3d& sp =
899 const Eigen::Isometry3d& tp =
903 const EigenSTL::vector_Vector3d* points = &
points_;
904 std::unique_ptr<EigenSTL::vector_Vector3d> temp_points;
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();
914 shapes::Mesh* m =
new shapes::Mesh();
916 m->vertices =
new double[m->vertex_count * 3];
918 m->triangles =
new unsigned int[m->triangle_count * 3];
922 m->vertices[0] = sp.translation().x();
923 m->vertices[1] = sp.translation().y();
924 m->vertices[2] = sp.translation().z();
927 m->vertices[3] = tp.translation().x();
928 m->vertices[4] = tp.translation().y();
929 m->vertices[5] = tp.translation().z();
932 for (std::size_t i = 0; i < points->size(); ++i)
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();
940 std::size_t p3 = points->size() * 3;
941 for (std::size_t i = 1; i < points->size(); ++i)
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;
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;
956 m->triangles[p3 - 3] = points->size() + 1;
957 m->triangles[p3 - 2] = 0;
958 m->triangles[p3 - 1] = 2;
960 m->triangles[p3 - 3] = points->size() + 1;
961 m->triangles[p3 - 2] = 1;
962 m->triangles[p3 - 1] = 2;
968 visualization_msgs::msg::MarkerArray& markers)
const
971 visualization_msgs::msg::Marker mk;
972 shapes::constructMarkerFromShape(m, mk);
975 mk.header.stamp = rclcpp::Clock().now();
976 mk.ns =
"constraints";
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);
994 markers.markers.push_back(mk);
998 const Eigen::Isometry3d& sp =
1001 const Eigen::Isometry3d& tp =
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;
1010 mka.header = mk.header;
1013 mka.lifetime = mk.lifetime;
1017 mka.points.resize(2);
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);
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();
1039 markers.markers.push_back(mka);
1051 const Eigen::Isometry3d& sp =
1054 const Eigen::Isometry3d& tp =
1063 double dp = normal2.dot(normal1);
1064 double ang = acos(dp);
1068 RCLCPP_INFO(LOGGER,
"Visibility constraint is violated because the sensor is looking at "
1076 "Visibility constraint is violated because the view angle is %lf "
1077 "(above the maximum allowed of %lf)",
1084 const Eigen::Vector3d& dir = (tp.translation() - sp.translation()).normalized();
1085 double dp = normal2.dot(dir);
1089 RCLCPP_INFO(LOGGER,
"Visibility constraint is violated because the sensor is looking at "
1094 double ang = acos(dp);
1099 "Visibility constraint is violated because the range angle is %lf "
1100 "(above the maximum allowed of %lf)",
1112 collision_env_->getWorld()->addToObject(
"cone", shapes::ShapeConstPtr(m), Eigen::Isometry3d::Identity());
1130 std::stringstream ss;
1132 RCLCPP_INFO(LOGGER,
"Visibility constraint %ssatisfied. Visibility cone approximation:\n %s",
1133 res.
collision ?
"not " :
"", ss.str().c_str());
1151 RCLCPP_DEBUG(LOGGER,
"Accepted collision with either sensor or target");
1159 RCLCPP_DEBUG(LOGGER,
"Accepted collision with either sensor or target");
1169 out <<
"Visibility constraint for sensor in frame '" <<
sensor_frame_id_ <<
"' using target in frame '"
1174 out <<
"No constraint" <<
'\n';
1190 for (
const moveit_msgs::msg::JointConstraint& joint_constraint : jc)
1193 bool u = ev->
configure(joint_constraint);
1194 result = result && u;
1206 for (
const moveit_msgs::msg::PositionConstraint& position_constraint : pc)
1209 bool u = ev->
configure(position_constraint, tf);
1210 result = result && u;
1222 for (
const moveit_msgs::msg::OrientationConstraint& orientation_constraint : oc)
1225 bool u = ev->
configure(orientation_constraint, tf);
1226 result = result && u;
1229 all_constraints_.orientation_constraints.push_back(orientation_constraint);
1238 for (
const moveit_msgs::msg::VisibilityConstraint& visibility_constraint : vc)
1241 bool u = ev->
configure(visibility_constraint, tf);
1242 result = result && u;
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;
1273 std::vector<ConstraintEvaluationResult>& results,
1282 result.
distance += results[i].distance;
1292 kinematic_constraint->print(out);
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.
double joint_tolerance_above_
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.
void clear()
Clear the stored constraints.
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.
virtual ~KinematicConstraint()
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.
double absolute_y_axis_tolerance_
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.
double absolute_x_axis_tolerance_
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...
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
const std::string & getName() const
Get the name of the joint.
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.
const std::string & getName() const
The name of this link.
bool isContinuous() const
Check if this joint wraps around.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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...
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.
@ 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
Representation and evaluation of kinematic constraints.
std::tuple< Eigen::Matrix< typename Eigen::MatrixBase< Derived >::Scalar, 3, 1 >, bool > CalcEulerAngles(const Eigen::MatrixBase< Derived > &R)
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.
bool collision
True if collision was found, false otherwise.
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.