Public Member Functions | Protected Attributes | List of all members
kinematic_constraints::OrientationConstraint Class Reference

Class for constraints on the orientation of a link. More...

#include <kinematic_constraint.h>

Inheritance diagram for kinematic_constraints::OrientationConstraint:
Inheritance graph
[legend]

Public Member Functions

void clear () override
 Clear the stored constraint. More...
 
bool configure (const moveit_msgs::OrientationConstraint &oc, const moveit::core::Transforms &tf)
 Configure the constraint based on a moveit_msgs::OrientationConstraint. 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...
 
bool equal (const KinematicConstraint &other, double margin) const override
 Check if two orientation constraints are the same. More...
 
const Eigen::Matrix3dgetDesiredRotationMatrix () const
 The rotation target in the reference or tf frame. More...
 
const Eigen::Matrix3dgetDesiredRotationMatrixInRefFrame () const
 The rotation target in the reference frame. More...
 
const moveit::core::LinkModelgetLinkModel () const
 Gets the subject link model. More...
 
int getParameterizationType () const
 
const std::string & getReferenceFrame () const
 The target frame of the planning_models::Transforms class, for interpreting the rotation 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...
 
bool mobileReferenceFrame () const
 Whether or not a mobile reference frame is being employed. More...
 
 OrientationConstraint (const moveit::core::RobotModelConstPtr &model)
 Constructor. More...
 
void print (std::ostream &out=std::cout) const override
 Print the constraint data. More...
 
- Public Member Functions inherited from kinematic_constraints::KinematicConstraint
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
 
ConstraintType getType () const
 Get the type of constraint. More...
 
 KinematicConstraint (const moveit::core::RobotModelConstPtr &model)
 Constructor. More...
 
virtual ~KinematicConstraint ()
 

Protected Attributes

double absolute_x_axis_tolerance_
 
double absolute_y_axis_tolerance_
 
double absolute_z_axis_tolerance_
 
Eigen::Matrix3d desired_R_in_frame_id_
 
std::string desired_rotation_frame_id_
 
Eigen::Matrix3d desired_rotation_matrix_
 
Eigen::Matrix3d desired_rotation_matrix_inv_
 
const moveit::core::LinkModellink_model_
 
bool mobile_frame_
 
int parameterization_type_
 
- Protected Attributes inherited from kinematic_constraints::KinematicConstraint
double constraint_weight_
 The weight of a constraint is a multiplicative factor associated to the distance computed by the decide() function
More...
 
moveit::core::RobotModelConstPtr robot_model_
 The kinematic model associated with this constraint. More...
 
ConstraintType type_
 The type of the constraint. 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...
 

Detailed Description

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 387 of file kinematic_constraint.h.

Constructor & Destructor Documentation

◆ OrientationConstraint()

kinematic_constraints::OrientationConstraint::OrientationConstraint ( const moveit::core::RobotModelConstPtr &  model)
inline

Constructor.

Parameters
[in]modelThe kinematic model used for constraint evaluation

Definition at line 398 of file kinematic_constraint.h.

Member Function Documentation

◆ clear()

void kinematic_constraints::OrientationConstraint::clear ( )
overridevirtual

Clear the stored constraint.

Implements kinematic_constraints::KinematicConstraint.

Definition at line 685 of file kinematic_constraint.cpp.

◆ configure()

bool kinematic_constraints::OrientationConstraint::configure ( const moveit_msgs::OrientationConstraint &  oc,
const moveit::core::Transforms tf 
)

Configure the constraint based on a moveit_msgs::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.

Parameters
[in]ocOrientationConstraint for configuration
Returns
True if constraint can be configured from oc

Definition at line 585 of file kinematic_constraint.cpp.

◆ decide()

ConstraintEvaluationResult kinematic_constraints::OrientationConstraint::decide ( const moveit::core::RobotState state,
bool  verbose = false 
) const
overridevirtual

Decide whether the constraint is satisfied in the indicated state.

Parameters
[in]stateThe kinematic state used for evaluation
[in]verboseWhether or not to print output
Returns

Implements kinematic_constraints::KinematicConstraint.

Definition at line 700 of file kinematic_constraint.cpp.

◆ enabled()

bool kinematic_constraints::OrientationConstraint::enabled ( ) const
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 695 of file kinematic_constraint.cpp.

◆ equal()

bool kinematic_constraints::OrientationConstraint::equal ( const KinematicConstraint other,
double  margin 
) const
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:

  • The link must be the same
  • The rotations specified by the quaternions must be within the margin
  • The tolerances must all be within the margin
Parameters
[in]otherThe other constraint to test
[in]marginThe margin to apply to all values associated with constraint
Returns
True if equal, otherwise false

Implements kinematic_constraints::KinematicConstraint.

Definition at line 667 of file kinematic_constraint.cpp.

◆ getDesiredRotationMatrix()

const Eigen::Matrix3d& kinematic_constraints::OrientationConstraint::getDesiredRotationMatrix ( ) const
inline

The rotation target in the reference or tf frame.

Returns
The target rotation.

The returned matrix is always a valid rotation matrix.

Definition at line 495 of file kinematic_constraint.h.

◆ getDesiredRotationMatrixInRefFrame()

const Eigen::Matrix3d& kinematic_constraints::OrientationConstraint::getDesiredRotationMatrixInRefFrame ( ) const
inline

The rotation target in the reference frame.

Returns
The target rotation.

The returned matrix is always a valid rotation matrix.

Definition at line 482 of file kinematic_constraint.h.

◆ getLinkModel()

const moveit::core::LinkModel* kinematic_constraints::OrientationConstraint::getLinkModel ( ) const
inline

Gets the subject link model.

Returns
Returns the current link model

Definition at line 448 of file kinematic_constraint.h.

◆ getParameterizationType()

int kinematic_constraints::OrientationConstraint::getParameterizationType ( ) const
inline

Definition at line 534 of file kinematic_constraint.h.

◆ getReferenceFrame()

const std::string& kinematic_constraints::OrientationConstraint::getReferenceFrame ( ) const
inline

The target frame of the planning_models::Transforms class, for interpreting the rotation frame.

Returns
The reference frame.

Definition at line 459 of file kinematic_constraint.h.

◆ getXAxisTolerance()

double kinematic_constraints::OrientationConstraint::getXAxisTolerance ( ) const
inline

Gets the X axis tolerance.

Returns
The X axis tolerance

Definition at line 507 of file kinematic_constraint.h.

◆ getYAxisTolerance()

double kinematic_constraints::OrientationConstraint::getYAxisTolerance ( ) const
inline

Gets the Y axis tolerance.

Returns
The Y axis tolerance

Definition at line 518 of file kinematic_constraint.h.

◆ getZAxisTolerance()

double kinematic_constraints::OrientationConstraint::getZAxisTolerance ( ) const
inline

Gets the Z axis tolerance.

Returns
The Z axis tolerance

Definition at line 529 of file kinematic_constraint.h.

◆ mobileReferenceFrame()

bool kinematic_constraints::OrientationConstraint::mobileReferenceFrame ( ) const
inline

Whether or not a mobile reference frame is being employed.

Returns
True if a mobile reference frame is being employed, and otherwise false.

Definition at line 470 of file kinematic_constraint.h.

◆ print()

void kinematic_constraints::OrientationConstraint::print ( std::ostream &  out = std::cout) const
overridevirtual

Print the constraint data.

Parameters
[in]outThe file descriptor for printing

Reimplemented from kinematic_constraints::KinematicConstraint.

Definition at line 775 of file kinematic_constraint.cpp.

Member Data Documentation

◆ absolute_x_axis_tolerance_

double kinematic_constraints::OrientationConstraint::absolute_x_axis_tolerance_
protected

Definition at line 547 of file kinematic_constraint.h.

◆ absolute_y_axis_tolerance_

double kinematic_constraints::OrientationConstraint::absolute_y_axis_tolerance_
protected

Definition at line 547 of file kinematic_constraint.h.

◆ absolute_z_axis_tolerance_

double kinematic_constraints::OrientationConstraint::absolute_z_axis_tolerance_
protected

Storage for the tolerances

Definition at line 548 of file kinematic_constraint.h.

◆ desired_R_in_frame_id_

Eigen::Matrix3d kinematic_constraints::OrientationConstraint::desired_R_in_frame_id_
protected

Desired rotation matrix in frame_id

Definition at line 541 of file kinematic_constraint.h.

◆ desired_rotation_frame_id_

std::string kinematic_constraints::OrientationConstraint::desired_rotation_frame_id_
protected

The target frame of the transform tree

Definition at line 544 of file kinematic_constraint.h.

◆ desired_rotation_matrix_

Eigen::Matrix3d kinematic_constraints::OrientationConstraint::desired_rotation_matrix_
protected

The desired rotation matrix in the tf frame

Definition at line 542 of file kinematic_constraint.h.

◆ desired_rotation_matrix_inv_

Eigen::Matrix3d kinematic_constraints::OrientationConstraint::desired_rotation_matrix_inv_
protected

The inverse of desired_rotation_matrix_ (for efficiency)

Definition at line 543 of file kinematic_constraint.h.

◆ link_model_

const moveit::core::LinkModel* kinematic_constraints::OrientationConstraint::link_model_
protected

The target link model

Definition at line 540 of file kinematic_constraint.h.

◆ mobile_frame_

bool kinematic_constraints::OrientationConstraint::mobile_frame_
protected

Whether or not the header frame is mobile or fixed

Definition at line 545 of file kinematic_constraint.h.

◆ parameterization_type_

int kinematic_constraints::OrientationConstraint::parameterization_type_
protected

Parameterization type for orientation tolerance

Definition at line 546 of file kinematic_constraint.h.


The documentation for this class was generated from the following files:


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:16