Class for handling single DOF joint constraints. More...
#include <kinematic_constraint.h>
Public Member Functions | |
void | clear () override |
Clear the stored constraint. More... | |
bool | configure (const moveit_msgs::JointConstraint &jc) |
Configure the constraint based on a moveit_msgs::JointConstraint. More... | |
ConstraintEvaluationResult | decide (const moveit::core::RobotState &state, bool verbose=false) const override |
Decide whether the constraint is satisfied in the indicated state. More... | |
bool | enabled () const override |
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... | |
bool | equal (const KinematicConstraint &other, double margin) const override |
Check if two joint constraints are the same. More... | |
double | getDesiredJointPosition () const |
Gets the desired position component of the constraint. More... | |
const moveit::core::JointModel * | getJointModel () const |
Get the joint model for which this constraint operates. More... | |
double | getJointToleranceAbove () const |
Gets the upper tolerance component of the joint constraint. More... | |
double | getJointToleranceBelow () const |
Gets the lower tolerance component of the joint constraint. More... | |
int | getJointVariableIndex () const |
const std::string & | getJointVariableName () const |
Gets the joint variable name, as known to the moveit::core::RobotModel. More... | |
const std::string & | getLocalVariableName () const |
Gets the local variable name if this constraint was configured for a part of a multi-DOF joint. More... | |
JointConstraint (const moveit::core::RobotModelConstPtr &model) | |
Constructor. More... | |
void | print (std::ostream &out=std::cout) const override |
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 moveit::core::RobotModelConstPtr & | getRobotModel () const |
ConstraintType | getType () const |
Get the type of constraint. More... | |
KinematicConstraint (const moveit::core::RobotModelConstPtr &model) | |
Constructor. More... | |
virtual | ~KinematicConstraint () |
Protected Attributes | |
bool | joint_is_continuous_ |
Whether or not the joint is continuous. More... | |
const moveit::core::JointModel * | joint_model_ |
The joint from the kinematic model for this constraint. More... | |
double | joint_position_ |
double | joint_tolerance_above_ |
double | joint_tolerance_below_ |
Position and tolerance values. More... | |
int | joint_variable_index_ |
The index of the joint variable name in the full robot state. More... | |
std::string | joint_variable_name_ |
The joint variable name. More... | |
std::string | local_variable_name_ |
The local variable name for a multi DOF joint, if any. 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... | |
moveit::core::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... | |
Class for handling single DOF joint constraints.
This class handles single DOF constraints expressed as a tolerance above and below a target position. Multi-DOF joints can be accomodated by using local name formulations - i.e. for a planar joint specifying a constraint in terms of "planar_joint_name"/x.
Continuous revolute single DOF joints will be evaluated based on wrapping around 3.14 and -3.14. Tolerances above and below will be evaluating over the wrap. For instance, if the constraint value is 3.14 and the tolerance above is .04, a value of -3.14 is in bounds, as is a value of -3.12. -3.1 is out of bounds. Similarly, if the value of the constraint is -3.14, the tolerance above is .04, and the tolerance below is .02 then -3.1 is a valid value, as is 3.14; 3.1 is out of bounds.
Type will be JOINT_CONSTRAINT.
Definition at line 235 of file kinematic_constraint.h.
|
inline |
Constructor.
[in] | model | The kinematic model used for constraint evaluation |
Definition at line 243 of file kinematic_constraint.h.
|
overridevirtual |
Clear the stored constraint.
Implements kinematic_constraints::KinematicConstraint.
Definition at line 334 of file kinematic_constraint.cpp.
bool kinematic_constraints::JointConstraint::configure | ( | const moveit_msgs::JointConstraint & | jc | ) |
Configure the constraint based on a moveit_msgs::JointConstraint.
For the configure command to be successful, the joint must exist in the kinematic model, the joint must not be a multi-DOF joint (for these joints, local variables should be used), and the tolerance values must be positive.
[in] | jc | JointConstraint for configuration |
Definition at line 152 of file kinematic_constraint.cpp.
|
overridevirtual |
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 |
Implements kinematic_constraints::KinematicConstraint.
Definition at line 296 of file kinematic_constraint.cpp.
|
overridevirtual |
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 329 of file kinematic_constraint.cpp.
|
overridevirtual |
Check if two joint 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 joint constraints, they must act on the same joint, and the position and tolerance values must be within the margins.
[in] | other | The other constraint to test |
[in] | margin | The margin to apply to all values associated with constraint |
Implements kinematic_constraints::KinematicConstraint.
Definition at line 284 of file kinematic_constraint.cpp.
|
inline |
Gets the desired position component of the constraint.
Definition at line 331 of file kinematic_constraint.h.
|
inline |
Get the joint model for which this constraint operates.
Definition at line 291 of file kinematic_constraint.h.
|
inline |
Gets the upper tolerance component of the joint constraint.
Definition at line 342 of file kinematic_constraint.h.
|
inline |
Gets the lower tolerance component of the joint constraint.
Definition at line 353 of file kinematic_constraint.h.
|
inline |
Definition at line 320 of file kinematic_constraint.h.
|
inline |
Gets the joint variable name, as known to the moveit::core::RobotModel.
This will include the local variable name if a variable of a multi-DOF joint is constrained.
Definition at line 315 of file kinematic_constraint.h.
|
inline |
Gets the local variable name if this constraint was configured for a part of a multi-DOF joint.
Definition at line 303 of file kinematic_constraint.h.
|
overridevirtual |
Print the constraint data.
[in] | out | The file descriptor for printing |
Reimplemented from kinematic_constraints::KinematicConstraint.
Definition at line 344 of file kinematic_constraint.cpp.
|
protected |
Whether or not the joint is continuous.
Definition at line 360 of file kinematic_constraint.h.
|
protected |
The joint from the kinematic model for this constraint.
Definition at line 359 of file kinematic_constraint.h.
|
protected |
Definition at line 364 of file kinematic_constraint.h.
|
protected |
Definition at line 364 of file kinematic_constraint.h.
|
protected |
Position and tolerance values.
Definition at line 364 of file kinematic_constraint.h.
|
protected |
The index of the joint variable name in the full robot state.
Definition at line 363 of file kinematic_constraint.h.
|
protected |
The joint variable name.
Definition at line 362 of file kinematic_constraint.h.
|
protected |
The local variable name for a multi DOF joint, if any.
Definition at line 361 of file kinematic_constraint.h.