@@ -336,12 +336,19 @@ MOVEIT_CLASS_FORWARD(OrientationConstraint); // Defines OrientationConstraintPt
336336/* *
337337 * \brief Class for constraints on the orientation of a link
338338 *
339- * This class expresses an orientation constraint on a particular
340- * link. The constraint is specified in terms of a quaternion, with
341- * tolerances on X,Y, and Z axes. The rotation difference is computed
342- * based on the XYZ Euler angle formulation (intrinsic rotations) or as a rotation vector. This depends on the
343- * `Parameterization` type. The header on the quaternion can be specified in terms of either a fixed or a mobile
344- * frame. The type value will return ORIENTATION_CONSTRAINT.
339+ * This class expresses an orientation constraint on a particular link.
340+ * The constraint specifies a target orientation via a quaternion as well as
341+ * tolerances on X,Y, and Z rotation axes.
342+ * The rotation difference between the target and actual link orientation is expressed
343+ * either as XYZ Euler angles or as a rotation vector (depending on the `parameterization` type).
344+ * The latter is highly recommended, because it supports resolution of subframes and attached bodies.
345+ * Also, rotation vector representation allows to interpret the tolerances always w.r.t. the given reference frame.
346+ * Euler angles are much more restricted and exhibit singularities.
347+ *
348+ * For efficiency, if the target orientation is expressed w.r.t. to a fixed frame (relative to the planning frame),
349+ * some stuff is precomputed. However, mobile reference frames are supported as well.
350+ *
351+ * The type value will return ORIENTATION_CONSTRAINT.
345352 *
346353 */
347354class OrientationConstraint : public KinematicConstraint
@@ -439,6 +446,19 @@ class OrientationConstraint : public KinematicConstraint
439446 *
440447 * The returned matrix is always a valid rotation matrix.
441448 */
449+ const Eigen::Matrix3d& getDesiredRotationMatrixInRefFrame () const
450+ {
451+ // validity of the rotation matrix is enforced in configure()
452+ return desired_R_in_frame_id_;
453+ }
454+
455+ /* *
456+ * \brief The rotation target in the reference or tf frame.
457+ *
458+ * @return The target rotation.
459+ *
460+ * The returned matrix is always a valid rotation matrix.
461+ */
442462 const Eigen::Matrix3d& getDesiredRotationMatrix () const
443463 {
444464 // validity of the rotation matrix is enforced in configure()
@@ -484,16 +504,15 @@ class OrientationConstraint : public KinematicConstraint
484504 }
485505
486506protected:
487- const moveit::core::LinkModel* link_model_; /* *< \brief The target link model */
488- Eigen::Matrix3d desired_rotation_matrix_; /* *< \brief The desired rotation matrix in the tf frame. Guaranteed to
489- * be valid rotation matrix. */
490- Eigen::Matrix3d desired_rotation_matrix_inv_; /* *< \brief The inverse of the desired rotation matrix, precomputed for
491- * efficiency. Guaranteed to be valid rotation matrix. */
492- std::string desired_rotation_frame_id_; /* *< \brief The target frame of the transform tree */
493- bool mobile_frame_; /* *< \brief Whether or not the header frame is mobile or fixed */
494- int parameterization_type_; /* *< \brief Parameterization type for orientation tolerance. */
507+ const moveit::core::LinkModel* link_model_; /* *< The target link model */
508+ Eigen::Matrix3d desired_R_in_frame_id_; /* *< Desired rotation matrix in frame_id */
509+ Eigen::Matrix3d desired_rotation_matrix_; /* *< The desired rotation matrix in the tf frame */
510+ Eigen::Matrix3d desired_rotation_matrix_inv_; /* *< The inverse of desired_rotation_matrix_ (for efficiency) */
511+ std::string desired_rotation_frame_id_; /* *< The target frame of the transform tree */
512+ bool mobile_frame_; /* *< Whether or not the header frame is mobile or fixed */
513+ int parameterization_type_; /* *< Parameterization type for orientation tolerance */
495514 double absolute_x_axis_tolerance_, absolute_y_axis_tolerance_,
496- absolute_z_axis_tolerance_; /* *< \brief Storage for the tolerances */
515+ absolute_z_axis_tolerance_; /* *< Storage for the tolerances */
497516};
498517
499518MOVEIT_CLASS_FORWARD (PositionConstraint); // Defines PositionConstraintPtr, ConstPtr, WeakPtr... etc
0 commit comments