moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Class for constraints on the orientation of a link. More...
#include <kinematic_constraint.h>
Public Member Functions | |
OrientationConstraint (const moveit::core::RobotModelConstPtr &model) | |
Constructor. | |
bool | configure (const moveit_msgs::msg::OrientationConstraint &oc, const moveit::core::Transforms &tf) |
Configure the constraint based on a moveit_msgs::msg::OrientationConstraint. | |
bool | equal (const KinematicConstraint &other, double margin) const override |
Check if two orientation constraints are the same. | |
void | clear () override |
Clear the stored constraint. | |
ConstraintEvaluationResult | decide (const moveit::core::RobotState &state, bool verbose=false) const override |
Decide whether the constraint is satisfied in the indicated state. | |
bool | enabled () const override |
This function returns true if this constraint is configured and able to decide whether states do meet the constraint or not. If this function returns false it means that decide() will always return true – there is no constraint to be checked. | |
void | print (std::ostream &out=std::cout) const override |
Print the constraint data. | |
const moveit::core::LinkModel * | getLinkModel () const |
Gets the subject link model. | |
const std::string & | getReferenceFrame () const |
The target frame of the planning_models::Transforms class, for interpreting the rotation frame. | |
bool | mobileReferenceFrame () const |
Whether or not a mobile reference frame is being employed. | |
const Eigen::Matrix3d & | getDesiredRotationMatrixInRefFrame () const |
The rotation target in the reference frame. | |
const Eigen::Matrix3d & | getDesiredRotationMatrix () const |
The rotation target in the reference or tf frame. | |
double | getXAxisTolerance () const |
Gets the X axis tolerance. | |
double | getYAxisTolerance () const |
Gets the Y axis tolerance. | |
double | getZAxisTolerance () const |
Gets the Z axis tolerance. | |
int | getParameterizationType () const |
Public Member Functions inherited from kinematic_constraints::KinematicConstraint | |
KinematicConstraint (const moveit::core::RobotModelConstPtr &model) | |
Constructor. | |
virtual | ~KinematicConstraint () |
ConstraintType | getType () const |
Get the type of constraint. | |
double | getConstraintWeight () const |
The weight of a constraint is a multiplicative factor associated to the distance computed by the decide() function. | |
const moveit::core::RobotModelConstPtr & | getRobotModel () const |
Protected Attributes | |
const moveit::core::LinkModel * | link_model_ |
Eigen::Matrix3d | desired_R_in_frame_id_ |
Eigen::Matrix3d | desired_rotation_matrix_ |
Eigen::Matrix3d | desired_rotation_matrix_inv_ |
std::string | desired_rotation_frame_id_ |
bool | mobile_frame_ |
int | parameterization_type_ |
double | absolute_x_axis_tolerance_ |
double | absolute_y_axis_tolerance_ |
double | absolute_z_axis_tolerance_ |
Protected Attributes inherited from kinematic_constraints::KinematicConstraint | |
ConstraintType | type_ |
The type of the constraint. | |
moveit::core::RobotModelConstPtr | robot_model_ |
The kinematic model associated with this constraint. | |
double | constraint_weight_ |
The weight of a constraint is a multiplicative factor associated to the distance computed by the decide() function | |
Additional Inherited Members | |
Public Types inherited from kinematic_constraints::KinematicConstraint | |
enum | ConstraintType { UNKNOWN_CONSTRAINT , JOINT_CONSTRAINT , POSITION_CONSTRAINT , ORIENTATION_CONSTRAINT , VISIBILITY_CONSTRAINT } |
Enum for representing a constraint. More... | |
Class for constraints on the orientation of a link.
This class expresses an orientation constraint on a particular link. The constraint specifies a target orientation via a quaternion as well as tolerances on X,Y, and Z rotation axes. The rotation difference between the target and actual link orientation is expressed either as XYZ Euler angles or as a rotation vector (depending on the parameterization
type). The latter is highly recommended, because it supports resolution of subframes and attached bodies. Also, rotation vector representation allows to interpret the tolerances always w.r.t. the given reference frame. Euler angles are much more restricted and exhibit singularities.
For efficiency, if the target orientation is expressed w.r.t. to a fixed frame (relative to the planning frame), some stuff is precomputed. However, mobile reference frames are supported as well.
The type value will return ORIENTATION_CONSTRAINT.
Definition at line 354 of file kinematic_constraint.h.
|
inline |
Constructor.
[in] | model | The kinematic model used for constraint evaluation |
Definition at line 365 of file kinematic_constraint.h.
|
overridevirtual |
Clear the stored constraint.
Implements kinematic_constraints::KinematicConstraint.
Definition at line 693 of file kinematic_constraint.cpp.
bool kinematic_constraints::OrientationConstraint::configure | ( | const moveit_msgs::msg::OrientationConstraint & | oc, |
const moveit::core::Transforms & | tf | ||
) |
Configure the constraint based on a moveit_msgs::msg::OrientationConstraint.
For the configure command to be successful, the link must exist in the kinematic model. Note that if the absolute tolerance values are left as 0.0 only values less than a very small epsilon will evaluate to satisfied.
[in] | oc | OrientationConstraint for configuration |
Definition at line 594 of file kinematic_constraint.cpp.
|
overridevirtual |
Decide whether the constraint is satisfied in the indicated state.
[in] | state | The kinematic state used for evaluation |
[in] | verbose | Whether or not to print output |
Implements kinematic_constraints::KinematicConstraint.
Definition at line 708 of file kinematic_constraint.cpp.
|
overridevirtual |
This function returns true if this constraint is configured and able to decide whether states do meet the constraint or not. If this function returns false it means that decide() will always return true – there is no constraint to be checked.
Implements kinematic_constraints::KinematicConstraint.
Definition at line 703 of file kinematic_constraint.cpp.
|
overridevirtual |
Check if two orientation constraints are the same.
This means that the types are the same, the subject of the constraint is the same, and all values associated with the constraint are within a margin. The other constraint must also be enabled. For this to be true of orientation constraints:
[in] | other | The other constraint to test |
[in] | margin | The margin to apply to all values associated with constraint |
Implements kinematic_constraints::KinematicConstraint.
Definition at line 675 of file kinematic_constraint.cpp.
|
inline |
The rotation target in the reference or tf frame.
The returned matrix is always a valid rotation matrix.
Definition at line 462 of file kinematic_constraint.h.
|
inline |
The rotation target in the reference frame.
The returned matrix is always a valid rotation matrix.
Definition at line 449 of file kinematic_constraint.h.
|
inline |
Gets the subject link model.
Definition at line 415 of file kinematic_constraint.h.
|
inline |
|
inline |
The target frame of the planning_models::Transforms class, for interpreting the rotation frame.
Definition at line 426 of file kinematic_constraint.h.
|
inline |
Gets the X axis tolerance.
Definition at line 474 of file kinematic_constraint.h.
|
inline |
Gets the Y axis tolerance.
Definition at line 485 of file kinematic_constraint.h.
|
inline |
Gets the Z axis tolerance.
Definition at line 496 of file kinematic_constraint.h.
|
inline |
Whether or not a mobile reference frame is being employed.
Definition at line 437 of file kinematic_constraint.h.
|
overridevirtual |
Print the constraint data.
[in] | out | The file descriptor for printing |
Reimplemented from kinematic_constraints::KinematicConstraint.
Definition at line 782 of file kinematic_constraint.cpp.
|
protected |
Definition at line 514 of file kinematic_constraint.h.
|
protected |
Definition at line 514 of file kinematic_constraint.h.
|
protected |
Storage for the tolerances
Definition at line 515 of file kinematic_constraint.h.
|
protected |
Desired rotation matrix in frame_id
Definition at line 508 of file kinematic_constraint.h.
|
protected |
The target frame of the transform tree
Definition at line 511 of file kinematic_constraint.h.
|
protected |
The desired rotation matrix in the tf frame
Definition at line 509 of file kinematic_constraint.h.
|
protected |
The inverse of desired_rotation_matrix_ (for efficiency)
Definition at line 510 of file kinematic_constraint.h.
|
protected |
The target link model
Definition at line 507 of file kinematic_constraint.h.
|
protected |
Whether or not the header frame is mobile or fixed
Definition at line 512 of file kinematic_constraint.h.
|
protected |
Parameterization type for orientation tolerance
Definition at line 513 of file kinematic_constraint.h.