Class for constraints on the orientation of a link. More...
#include <kinematic_constraint.h>
Public Member Functions | |
virtual void | clear () |
Clear the stored constraint. | |
bool | configure (const moveit_msgs::OrientationConstraint &oc, const robot_state::Transforms &tf) |
Configure the constraint based on a moveit_msgs::OrientationConstraint. | |
virtual ConstraintEvaluationResult | decide (const robot_state::RobotState &state, bool verbose=false) const |
Decide whether the constraint is satisfied in the indicated state. | |
virtual bool | enabled () const |
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 |
Check if two orientation constraints are the same. | |
const Eigen::Matrix3d & | getDesiredRotationMatrix () const |
The rotation target in the reference frame. | |
const robot_model::LinkModel * | getLinkModel () const |
Gets the subject link model. | |
const std::string & | getReferenceFrame () const |
The target frame of the planning_models::Transforms class, for interpreting the rotation frame. | |
double | getXAxisTolerance () const |
Gets the X axis tolerance. | |
double | getYAxisTolerance () const |
Gets the Y axis tolerance. | |
double | getZAxisTolerance () const |
Gets the Z axis tolerance. | |
bool | mobileReferenceFrame () const |
Whether or not a mobile reference frame is being employed. | |
OrientationConstraint (const robot_model::RobotModelConstPtr &model) | |
Constructor. | |
virtual void | print (std::ostream &out=std::cout) const |
Print the constraint data. | |
Protected Attributes | |
double | absolute_x_axis_tolerance_ |
double | absolute_y_axis_tolerance_ |
double | absolute_z_axis_tolerance_ |
Storage for the tolerances. | |
std::string | desired_rotation_frame_id_ |
The target frame of the transform tree. | |
Eigen::Matrix3d | desired_rotation_matrix_ |
The desired rotation matrix in the tf frame. | |
Eigen::Matrix3d | desired_rotation_matrix_inv_ |
The inverse of the desired rotation matrix, precomputed for efficiency. | |
const robot_model::LinkModel * | link_model_ |
The target link model. | |
bool | mobile_frame_ |
Whether or not the header frame is mobile or fixed. |
Class for constraints on the orientation of a link.
This class expresses an orientation constraint on a particular link. The constraint is specified in terms of a quaternion, with tolerances on X,Y, and Z axes. The rotation difference is computed based on the ZXZ Euler angle formulation. The header on the quaternion can be specified in terms of either a fixed frame or a mobile frame. The type value will return ORIENTATION_CONSTRAINT.
Definition at line 335 of file kinematic_constraint.h.
kinematic_constraints::OrientationConstraint::OrientationConstraint | ( | const robot_model::RobotModelConstPtr & | model | ) | [inline] |
Constructor.
[in] | model | The kinematic model used for constraint evaluation |
Definition at line 346 of file kinematic_constraint.h.
void kinematic_constraints::OrientationConstraint::clear | ( | ) | [virtual] |
Clear the stored constraint.
Implements kinematic_constraints::KinematicConstraint.
Definition at line 592 of file kinematic_constraint.cpp.
bool kinematic_constraints::OrientationConstraint::configure | ( | const moveit_msgs::OrientationConstraint & | oc, |
const robot_state::Transforms & | tf | ||
) |
Configure the constraint based on a moveit_msgs::OrientationConstraint.
For the configure command to be successful, the link must exist in the kinematic model. Note that if the absolute tolerance values are left as 0.0 only values less than a very small epsilon will evaluate to satisfied.
[in] | oc | OrientationConstraint for configuration |
Definition at line 513 of file kinematic_constraint.cpp.
kinematic_constraints::ConstraintEvaluationResult kinematic_constraints::OrientationConstraint::decide | ( | const robot_state::RobotState & | state, |
bool | verbose = false |
||
) | const [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 |
Implements kinematic_constraints::KinematicConstraint.
Definition at line 607 of file kinematic_constraint.cpp.
bool kinematic_constraints::OrientationConstraint::enabled | ( | ) | const [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.
Implements kinematic_constraints::KinematicConstraint.
Definition at line 602 of file kinematic_constraint.cpp.
bool kinematic_constraints::OrientationConstraint::equal | ( | const KinematicConstraint & | other, |
double | margin | ||
) | const [virtual] |
Check if two orientation 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 orientation constraints:
[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 574 of file kinematic_constraint.cpp.
const Eigen::Matrix3d& kinematic_constraints::OrientationConstraint::getDesiredRotationMatrix | ( | ) | const [inline] |
The rotation target in the reference frame.
Definition at line 427 of file kinematic_constraint.h.
const robot_model::LinkModel* kinematic_constraints::OrientationConstraint::getLinkModel | ( | ) | const [inline] |
Gets the subject link model.
Definition at line 395 of file kinematic_constraint.h.
const std::string& kinematic_constraints::OrientationConstraint::getReferenceFrame | ( | ) | const [inline] |
The target frame of the planning_models::Transforms class, for interpreting the rotation frame.
Definition at line 406 of file kinematic_constraint.h.
double kinematic_constraints::OrientationConstraint::getXAxisTolerance | ( | ) | const [inline] |
Gets the X axis tolerance.
Definition at line 438 of file kinematic_constraint.h.
double kinematic_constraints::OrientationConstraint::getYAxisTolerance | ( | ) | const [inline] |
Gets the Y axis tolerance.
Definition at line 449 of file kinematic_constraint.h.
double kinematic_constraints::OrientationConstraint::getZAxisTolerance | ( | ) | const [inline] |
Gets the Z axis tolerance.
Definition at line 460 of file kinematic_constraint.h.
bool kinematic_constraints::OrientationConstraint::mobileReferenceFrame | ( | ) | const [inline] |
Whether or not a mobile reference frame is being employed.
Definition at line 417 of file kinematic_constraint.h.
void kinematic_constraints::OrientationConstraint::print | ( | std::ostream & | out = std::cout | ) | const [virtual] |
Print the constraint data.
[in] | out | The file descriptor for printing |
Reimplemented from kinematic_constraints::KinematicConstraint.
Definition at line 655 of file kinematic_constraint.cpp.
double kinematic_constraints::OrientationConstraint::absolute_x_axis_tolerance_ [protected] |
Definition at line 472 of file kinematic_constraint.h.
double kinematic_constraints::OrientationConstraint::absolute_y_axis_tolerance_ [protected] |
Definition at line 472 of file kinematic_constraint.h.
double kinematic_constraints::OrientationConstraint::absolute_z_axis_tolerance_ [protected] |
Storage for the tolerances.
Definition at line 472 of file kinematic_constraint.h.
std::string kinematic_constraints::OrientationConstraint::desired_rotation_frame_id_ [protected] |
The target frame of the transform tree.
Definition at line 470 of file kinematic_constraint.h.
Eigen::Matrix3d kinematic_constraints::OrientationConstraint::desired_rotation_matrix_ [protected] |
The desired rotation matrix in the tf frame.
Definition at line 468 of file kinematic_constraint.h.
Eigen::Matrix3d kinematic_constraints::OrientationConstraint::desired_rotation_matrix_inv_ [protected] |
The inverse of the desired rotation matrix, precomputed for efficiency.
Definition at line 469 of file kinematic_constraint.h.
const robot_model::LinkModel* kinematic_constraints::OrientationConstraint::link_model_ [protected] |
The target link model.
Definition at line 467 of file kinematic_constraint.h.
bool kinematic_constraints::OrientationConstraint::mobile_frame_ [protected] |
Whether or not the header frame is mobile or fixed.
Definition at line 471 of file kinematic_constraint.h.