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. More... | |
bool | configure (const moveit_msgs::msg::OrientationConstraint &oc, const moveit::core::Transforms &tf) |
Configure the constraint based on a moveit_msgs::msg::OrientationConstraint. More... | |
bool | equal (const KinematicConstraint &other, double margin) const override |
Check if two orientation constraints are the same. More... | |
void | clear () override |
Clear the stored constraint. More... | |
ConstraintEvaluationResult | decide (const moveit::core::RobotState &state, bool verbose=false) const override |
Decide whether the constraint is satisfied in the indicated state. More... | |
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. More... | |
void | print (std::ostream &out=std::cout) const override |
Print the constraint data. More... | |
const moveit::core::LinkModel * | getLinkModel () const |
Gets the subject link model. More... | |
const std::string & | getReferenceFrame () const |
The target frame of the planning_models::Transforms class, for interpreting the rotation frame. More... | |
bool | mobileReferenceFrame () const |
Whether or not a mobile reference frame is being employed. More... | |
const Eigen::Matrix3d & | getDesiredRotationMatrix () const |
The rotation target in the reference frame. More... | |
double | getXAxisTolerance () const |
Gets the X axis tolerance. More... | |
double | getYAxisTolerance () const |
Gets the Y axis tolerance. More... | |
double | getZAxisTolerance () const |
Gets the Z axis tolerance. More... | |
int | getParameterizationType () const |
Public Member Functions inherited from kinematic_constraints::KinematicConstraint | |
KinematicConstraint (const moveit::core::RobotModelConstPtr &model) | |
Constructor. More... | |
virtual | ~KinematicConstraint () |
ConstraintType | getType () const |
Get the type of constraint. More... | |
double | getConstraintWeight () const |
The weight of a constraint is a multiplicative factor associated to the distance computed by the decide() function. More... | |
const moveit::core::RobotModelConstPtr & | getRobotModel () const |
Protected Attributes | |
const moveit::core::LinkModel * | link_model_ |
The target link model. More... | |
Eigen::Matrix3d | desired_rotation_matrix_ |
The desired rotation matrix in the tf frame. Guaranteed to be valid rotation matrix. More... | |
Eigen::Matrix3d | desired_rotation_matrix_inv_ |
The inverse of the desired rotation matrix, precomputed for efficiency. Guaranteed to be valid rotation matrix. More... | |
std::string | desired_rotation_frame_id_ |
The target frame of the transform tree. More... | |
bool | mobile_frame_ |
Whether or not the header frame is mobile or fixed. More... | |
int | parameterization_type_ |
Parameterization type for orientation tolerance. More... | |
double | absolute_x_axis_tolerance_ |
double | absolute_y_axis_tolerance_ |
double | absolute_z_axis_tolerance_ |
Storage for the tolerances. More... | |
Protected Attributes inherited from kinematic_constraints::KinematicConstraint | |
ConstraintType | type_ |
The type of the constraint. More... | |
moveit::core::RobotModelConstPtr | robot_model_ |
The kinematic model associated with this constraint. More... | |
double | constraint_weight_ |
The weight of a constraint is a multiplicative factor associated to the distance computed by the decide() function More... | |
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 is specified in terms of a quaternion, with tolerances on X,Y, and Z axes. The rotation difference is computed based on the XYZ Euler angle formulation (intrinsic rotations) or as a rotation vector. This depends on the Parameterization
type. The header on the quaternion can be specified in terms of either a fixed or a mobile frame. The type value will return ORIENTATION_CONSTRAINT.
Definition at line 347 of file kinematic_constraint.h.
|
inline |
Constructor.
[in] | model | The kinematic model used for constraint evaluation |
Definition at line 358 of file kinematic_constraint.h.
|
overridevirtual |
Clear the stored constraint.
Implements kinematic_constraints::KinematicConstraint.
Definition at line 655 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 558 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 670 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 665 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 637 of file kinematic_constraint.cpp.
|
inline |
The rotation target in the reference frame.
The returned matrix is always a valid rotation matrix.
Definition at line 442 of file kinematic_constraint.h.
|
inline |
Gets the subject link model.
Definition at line 408 of file kinematic_constraint.h.
|
inline |
|
inline |
The target frame of the planning_models::Transforms class, for interpreting the rotation frame.
Definition at line 419 of file kinematic_constraint.h.
|
inline |
Gets the X axis tolerance.
Definition at line 454 of file kinematic_constraint.h.
|
inline |
Gets the Y axis tolerance.
Definition at line 465 of file kinematic_constraint.h.
|
inline |
Gets the Z axis tolerance.
Definition at line 476 of file kinematic_constraint.h.
|
inline |
Whether or not a mobile reference frame is being employed.
Definition at line 430 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 746 of file kinematic_constraint.cpp.
|
protected |
Definition at line 495 of file kinematic_constraint.h.
|
protected |
Definition at line 495 of file kinematic_constraint.h.
|
protected |
Storage for the tolerances.
Definition at line 496 of file kinematic_constraint.h.
|
protected |
The target frame of the transform tree.
Definition at line 492 of file kinematic_constraint.h.
|
protected |
The desired rotation matrix in the tf frame. Guaranteed to be valid rotation matrix.
Definition at line 488 of file kinematic_constraint.h.
|
protected |
The inverse of the desired rotation matrix, precomputed for efficiency. Guaranteed to be valid rotation matrix.
Definition at line 490 of file kinematic_constraint.h.
|
protected |
The target link model.
Definition at line 487 of file kinematic_constraint.h.
|
protected |
Whether or not the header frame is mobile or fixed.
Definition at line 493 of file kinematic_constraint.h.
|
protected |
Parameterization type for orientation tolerance.
Definition at line 494 of file kinematic_constraint.h.