moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
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 | |
KinematicConstraint (const moveit::core::RobotModelConstPtr &model) | |
Constructor. | |
virtual | ~KinematicConstraint () |
virtual void | clear ()=0 |
Clear the stored constraint. | |
virtual ConstraintEvaluationResult | decide (const moveit::core::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. | |
ConstraintType | getType () const |
Get the type of constraint. | |
virtual void | print (std::ostream &=std::cout) const |
Print the constraint data. | |
double | getConstraintWeight () const |
The weight of a constraint is a multiplicative factor associated to the distance computed by the decide() function. | |
const moveit::core::RobotModelConstPtr & | getRobotModel () const |
Protected Attributes | |
ConstraintType | type_ |
The type of the constraint. | |
moveit::core::RobotModelConstPtr | robot_model_ |
The kinematic model associated with this constraint. | |
double | constraint_weight_ |
The weight of a constraint is a multiplicative factor associated to the distance computed by the decide() function | |
Base class for representing a kinematic constraint.
Definition at line 77 of file kinematic_constraint.h.
Enum for representing a constraint.
Enumerator | |
---|---|
UNKNOWN_CONSTRAINT | |
JOINT_CONSTRAINT | |
POSITION_CONSTRAINT | |
ORIENTATION_CONSTRAINT | |
VISIBILITY_CONSTRAINT |
Definition at line 81 of file kinematic_constraint.h.
kinematic_constraints::KinematicConstraint::KinematicConstraint | ( | const moveit::core::RobotModelConstPtr & | model | ) |
Constructor.
[in] | model | The kinematic model used for constraint evaluation |
Definition at line 133 of file kinematic_constraint.cpp.
|
virtualdefault |
|
pure virtual |
Clear the stored constraint.
Implemented in kinematic_constraints::JointConstraint, kinematic_constraints::OrientationConstraint, kinematic_constraints::PositionConstraint, and kinematic_constraints::VisibilityConstraint.
|
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::JointConstraint, kinematic_constraints::OrientationConstraint, kinematic_constraints::PositionConstraint, and kinematic_constraints::VisibilityConstraint.
|
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::JointConstraint, kinematic_constraints::OrientationConstraint, kinematic_constraints::PositionConstraint, and kinematic_constraints::VisibilityConstraint.
|
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::JointConstraint, kinematic_constraints::OrientationConstraint, kinematic_constraints::PositionConstraint, and kinematic_constraints::VisibilityConstraint.
|
inline |
The weight of a constraint is a multiplicative factor associated to the distance computed by the decide() function.
Definition at line 158 of file kinematic_constraint.h.
|
inline |
Definition at line 169 of file kinematic_constraint.h.
|
inline |
Get the type of constraint.
Definition at line 137 of file kinematic_constraint.h.
|
inlinevirtual |
Print the constraint data.
[in] | out | The file descriptor for printing |
Reimplemented in kinematic_constraints::JointConstraint, kinematic_constraints::OrientationConstraint, kinematic_constraints::PositionConstraint, and kinematic_constraints::VisibilityConstraint.
Definition at line 147 of file kinematic_constraint.h.
|
protected |
The weight of a constraint is a multiplicative factor associated to the distance computed by the decide() function
Definition at line 177 of file kinematic_constraint.h.
|
protected |
The kinematic model associated with this constraint.
Definition at line 176 of file kinematic_constraint.h.
|
protected |
The type of the constraint.
Definition at line 175 of file kinematic_constraint.h.