Public Types | Public Member Functions | Protected Attributes | List of all members
kinematic_constraints::KinematicConstraint Class Referenceabstract

Base class for representing a kinematic constraint. More...

#include <kinematic_constraint.h>

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

Public Types

enum  ConstraintType {
  UNKNOWN_CONSTRAINT, JOINT_CONSTRAINT, POSITION_CONSTRAINT, ORIENTATION_CONSTRAINT,
  VISIBILITY_CONSTRAINT
}
 Enum for representing a constraint. More...
 

Public Member Functions

virtual void clear ()=0
 Clear the stored constraint. More...
 
virtual ConstraintEvaluationResult decide (const robot_state::RobotState &state, bool verbose=false) const =0
 Decide whether the constraint is satisfied in the indicated state. More...
 
virtual bool enabled () const =0
 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 =0
 Check if two 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. More...
 
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 void print (std::ostream &=std::cout) const
 Print the constraint data. More...
 
virtual ~KinematicConstraint ()
 

Protected Attributes

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...
 

Detailed Description

Base class for representing a kinematic constraint.

Definition at line 78 of file kinematic_constraint.h.

Member Enumeration Documentation

Enum for representing a constraint.

Enumerator
UNKNOWN_CONSTRAINT 
JOINT_CONSTRAINT 
POSITION_CONSTRAINT 
ORIENTATION_CONSTRAINT 
VISIBILITY_CONSTRAINT 

Definition at line 82 of file kinematic_constraint.h.

Constructor & Destructor Documentation

kinematic_constraints::KinematicConstraint::KinematicConstraint ( const robot_model::RobotModelConstPtr &  model)

Constructor.

Parameters
[in]modelThe kinematic model used for constraint evaluation

Definition at line 61 of file kinematic_constraint.cpp.

kinematic_constraints::KinematicConstraint::~KinematicConstraint ( )
virtualdefault

Member Function Documentation

virtual void kinematic_constraints::KinematicConstraint::clear ( )
pure virtual
virtual ConstraintEvaluationResult kinematic_constraints::KinematicConstraint::decide ( const robot_state::RobotState state,
bool  verbose = false 
) const
pure 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

Implemented in kinematic_constraints::VisibilityConstraint, kinematic_constraints::PositionConstraint, kinematic_constraints::OrientationConstraint, and kinematic_constraints::JointConstraint.

virtual bool kinematic_constraints::KinematicConstraint::enabled ( ) const
pure 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.

Implemented in kinematic_constraints::VisibilityConstraint, kinematic_constraints::PositionConstraint, kinematic_constraints::OrientationConstraint, and kinematic_constraints::JointConstraint.

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

Check if two 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.

Parameters
[in]otherThe other constraint to test
[in]marginThe margin to apply to all values associated with constraint
Returns
True if equal, otherwise false

Implemented in kinematic_constraints::VisibilityConstraint, kinematic_constraints::PositionConstraint, kinematic_constraints::OrientationConstraint, and kinematic_constraints::JointConstraint.

double kinematic_constraints::KinematicConstraint::getConstraintWeight ( ) const
inline

The weight of a constraint is a multiplicative factor associated to the distance computed by the decide() function.

Returns
The constraint weight

Definition at line 159 of file kinematic_constraint.h.

const robot_model::RobotModelConstPtr& kinematic_constraints::KinematicConstraint::getRobotModel ( ) const
inline
Returns
The kinematic model associated with this constraint

Definition at line 170 of file kinematic_constraint.h.

ConstraintType kinematic_constraints::KinematicConstraint::getType ( ) const
inline

Get the type of constraint.

Returns
The constraint type

Definition at line 138 of file kinematic_constraint.h.

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

Print the constraint data.

Parameters
[in]outThe file descriptor for printing

Reimplemented in kinematic_constraints::VisibilityConstraint, kinematic_constraints::PositionConstraint, kinematic_constraints::OrientationConstraint, and kinematic_constraints::JointConstraint.

Definition at line 148 of file kinematic_constraint.h.

Member Data Documentation

double kinematic_constraints::KinematicConstraint::constraint_weight_
protected

The weight of a constraint is a multiplicative factor associated to the distance computed by the decide() function.

Definition at line 178 of file kinematic_constraint.h.

robot_model::RobotModelConstPtr kinematic_constraints::KinematicConstraint::robot_model_
protected

The kinematic model associated with this constraint.

Definition at line 177 of file kinematic_constraint.h.

ConstraintType kinematic_constraints::KinematicConstraint::type_
protected

The type of the constraint.

Definition at line 176 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