Base class for representing a kinematic constraint. More...
#include <kinematic_constraint.h>
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. |
Base class for representing a kinematic constraint.
Definition at line 76 of file kinematic_constraint.h.
Enum for representing a constraint.
UNKNOWN_CONSTRAINT | |
JOINT_CONSTRAINT | |
POSITION_CONSTRAINT | |
ORIENTATION_CONSTRAINT | |
VISIBILITY_CONSTRAINT |
Definition at line 81 of file kinematic_constraint.h.
kinematic_constraints::KinematicConstraint::KinematicConstraint | ( | const robot_model::RobotModelConstPtr & | model | ) |
Constructor.
[in] | model | The kinematic model used for constraint evaluation |
Definition at line 63 of file kinematic_constraint.cpp.
Definition at line 68 of file kinematic_constraint.cpp.
virtual void kinematic_constraints::KinematicConstraint::clear | ( | ) | [pure virtual] |
Clear the stored constraint.
Implemented in kinematic_constraints::VisibilityConstraint, kinematic_constraints::PositionConstraint, kinematic_constraints::OrientationConstraint, and kinematic_constraints::JointConstraint.
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.
[in] | state | The kinematic state used for evaluation |
[in] | verbose | Whether or not to print output |
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.
[in] | other | The other constraint to test |
[in] | margin | The margin to apply to all values associated with constraint |
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.
Definition at line 153 of file kinematic_constraint.h.
const robot_model::RobotModelConstPtr& kinematic_constraints::KinematicConstraint::getRobotModel | ( | ) | const [inline] |
Definition at line 164 of file kinematic_constraint.h.
ConstraintType kinematic_constraints::KinematicConstraint::getType | ( | ) | const [inline] |
Get the type of constraint.
Definition at line 133 of file kinematic_constraint.h.
virtual void kinematic_constraints::KinematicConstraint::print | ( | std::ostream & | out = std::cout | ) | const [inline, virtual] |
Print the constraint data.
[in] | out | The file descriptor for printing |
Reimplemented in kinematic_constraints::VisibilityConstraint, kinematic_constraints::PositionConstraint, kinematic_constraints::OrientationConstraint, and kinematic_constraints::JointConstraint.
Definition at line 143 of file kinematic_constraint.h.
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 173 of file kinematic_constraint.h.
robot_model::RobotModelConstPtr kinematic_constraints::KinematicConstraint::robot_model_ [protected] |
The kinematic model associated with this constraint.
Definition at line 172 of file kinematic_constraint.h.
The type of the constraint.
Definition at line 171 of file kinematic_constraint.h.