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

virtual void clear ()
 Clear the stored constraint. More...
 
bool configure (const moveit_msgs::OrientationConstraint &oc, const robot_state::Transforms &tf)
 Configure the constraint based on a moveit_msgs::OrientationConstraint. More...
 
virtual ConstraintEvaluationResult decide (const robot_state::RobotState &state, bool verbose=false) const
 Decide whether the constraint is satisfied in the indicated state. More...
 
virtual bool enabled () const
 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...
 
virtual bool equal (const KinematicConstraint &other, double margin) const
 Check if two orientation constraints are the same. More...
 
const Eigen::Matrix3d & getDesiredRotationMatrix () const
 The rotation target in the reference frame. More...
 
const robot_model::LinkModelgetLinkModel () 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...
 
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 robot_model::RobotModelConstPtr &model)
 Constructor. More...
 
virtual void print (std::ostream &out=std::cout) const
 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 robot_model::RobotModelConstPtr & getRobotModel () const
 
ConstraintType getType () const
 Get the type of constraint. More...
 
 KinematicConstraint (const robot_model::RobotModelConstPtr &model)
 Constructor. More...
 
virtual ~KinematicConstraint ()
 

Protected Attributes

double absolute_x_axis_tolerance_
 
double absolute_y_axis_tolerance_
 
double absolute_z_axis_tolerance_
 Storage for the tolerances. More...
 
std::string desired_rotation_frame_id_
 The target frame of the transform tree. More...
 
Eigen::Matrix3d desired_rotation_matrix_
 The desired rotation matrix in the tf frame. More...
 
Eigen::Matrix3d desired_rotation_matrix_inv_
 The inverse of the desired rotation matrix, precomputed for efficiency. More...
 
const robot_model::LinkModellink_model_
 The target link model. More...
 
bool mobile_frame_
 Whether or not the header frame is mobile or fixed. More...
 
- 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...
 
robot_model::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 is specified in terms of a quaternion, with tolerances on X,Y, and Z axes. The rotation difference is computed based on the ZXZ Euler angle formulation. The header on the quaternion can be specified in terms of either a fixed frame or a mobile frame. The type value will return ORIENTATION_CONSTRAINT.

Definition at line 348 of file kinematic_constraint.h.

Constructor & Destructor Documentation

kinematic_constraints::OrientationConstraint::OrientationConstraint ( const robot_model::RobotModelConstPtr &  model)
inline

Constructor.

Parameters
[in]modelThe kinematic model used for constraint evaluation

Definition at line 359 of file kinematic_constraint.h.

Member Function Documentation

void kinematic_constraints::OrientationConstraint::clear ( )
virtual

Clear the stored constraint.

Implements kinematic_constraints::KinematicConstraint.

Definition at line 577 of file kinematic_constraint.cpp.

bool kinematic_constraints::OrientationConstraint::configure ( const moveit_msgs::OrientationConstraint &  oc,
const robot_state::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 493 of file kinematic_constraint.cpp.

ConstraintEvaluationResult kinematic_constraints::OrientationConstraint::decide ( const robot_state::RobotState state,
bool  verbose = false 
) const
virtual

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 592 of file kinematic_constraint.cpp.

bool kinematic_constraints::OrientationConstraint::enabled ( ) const
virtual

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 587 of file kinematic_constraint.cpp.

bool kinematic_constraints::OrientationConstraint::equal ( const KinematicConstraint other,
double  margin 
) const
virtual

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 559 of file kinematic_constraint.cpp.

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

The rotation target in the reference frame.

Returns
The target rotation

Definition at line 440 of file kinematic_constraint.h.

const robot_model::LinkModel* kinematic_constraints::OrientationConstraint::getLinkModel ( ) const
inline

Gets the subject link model.

Returns
Returns the current link model

Definition at line 408 of file kinematic_constraint.h.

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

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

Gets the X axis tolerance.

Returns
The X axis tolerance

Definition at line 451 of file kinematic_constraint.h.

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

Gets the Y axis tolerance.

Returns
The Y axis tolerance

Definition at line 462 of file kinematic_constraint.h.

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

Gets the Z axis tolerance.

Returns
The Z axis tolerance

Definition at line 473 of file kinematic_constraint.h.

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

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

Print the constraint data.

Parameters
[in]outThe file descriptor for printing

Reimplemented from kinematic_constraints::KinematicConstraint.

Definition at line 633 of file kinematic_constraint.cpp.

Member Data Documentation

double kinematic_constraints::OrientationConstraint::absolute_x_axis_tolerance_
protected

Definition at line 486 of file kinematic_constraint.h.

double kinematic_constraints::OrientationConstraint::absolute_y_axis_tolerance_
protected

Definition at line 486 of file kinematic_constraint.h.

double kinematic_constraints::OrientationConstraint::absolute_z_axis_tolerance_
protected

Storage for the tolerances.

Definition at line 486 of file kinematic_constraint.h.

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

The target frame of the transform tree.

Definition at line 484 of file kinematic_constraint.h.

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

The desired rotation matrix in the tf frame.

Definition at line 480 of file kinematic_constraint.h.

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

The inverse of the desired rotation matrix, precomputed for efficiency.

Definition at line 481 of file kinematic_constraint.h.

const robot_model::LinkModel* kinematic_constraints::OrientationConstraint::link_model_
protected

The target link model.

Definition at line 479 of file kinematic_constraint.h.

bool kinematic_constraints::OrientationConstraint::mobile_frame_
protected

Whether or not the header frame is mobile or fixed.

Definition at line 485 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 Oct 18 2020 13:16:34