Public Types | Public Member Functions | Protected Attributes
kinematic_constraints::KinematicConstraint Class Reference

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

#include <kinematic_constraint.h>

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

List of all members.

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.
virtual ConstraintEvaluationResult decide (const robot_state::RobotState &state, bool verbose=false) const =0
 Decide whether the constraint is satisfied in the indicated state.
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.
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.
double getConstraintWeight () const
 The weight of a constraint is a multiplicative factor associated to the distance computed by the decide() function.
const
robot_model::RobotModelConstPtr & 
getRobotModel () const
ConstraintType getType () const
 Get the type of constraint.
 KinematicConstraint (const robot_model::RobotModelConstPtr &model)
 Constructor.
virtual void print (std::ostream &out=std::cout) const
 Print the constraint data.
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.
robot_model::RobotModelConstPtr robot_model_
 The kinematic model associated with this constraint.
ConstraintType type_
 The type of the constraint.

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

Definition at line 67 of file kinematic_constraint.cpp.


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.

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.

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 &  out = std::cout) const [inline, virtual]

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

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.

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 Wed Jun 19 2019 19:23:50