moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Class for constraints on the XYZ position of a link. More...
#include <kinematic_constraint.h>
Public Member Functions | |
PositionConstraint (const moveit::core::RobotModelConstPtr &model) | |
Constructor. | |
bool | configure (const moveit_msgs::msg::PositionConstraint &pc, const moveit::core::Transforms &tf) |
Configure the constraint based on a moveit_msgs::msg::PositionConstraint. | |
bool | equal (const KinematicConstraint &other, double margin) const override |
Check if two constraints are the same. For position constraints this means that: | |
void | clear () override |
Clear the stored constraint. | |
ConstraintEvaluationResult | decide (const moveit::core::RobotState &state, bool verbose=false) const override |
Decide whether the constraint is satisfied in the indicated state. | |
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. | |
void | print (std::ostream &out=std::cout) const override |
Print the constraint data. | |
const moveit::core::LinkModel * | getLinkModel () const |
Returns the associated link model, or nullptr if not enabled. | |
const Eigen::Vector3d & | getLinkOffset () const |
Returns the target offset. | |
bool | hasLinkOffset () const |
If the constraint is enabled and the link offset is substantially different than zero. | |
const std::vector< bodies::BodyPtr > & | getConstraintRegions () const |
Returns all the constraint regions. | |
const std::string & | getReferenceFrame () const |
Returns the reference frame. | |
bool | mobileReferenceFrame () const |
If enabled and the specified frame is a mobile frame, return true. Otherwise, returns false. | |
Public Member Functions inherited from kinematic_constraints::KinematicConstraint | |
KinematicConstraint (const moveit::core::RobotModelConstPtr &model) | |
Constructor. | |
virtual | ~KinematicConstraint () |
ConstraintType | getType () const |
Get the type of constraint. | |
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 | |
Eigen::Vector3d | offset_ |
The target offset. | |
bool | has_offset_ |
Whether the offset is substantially different than 0.0. | |
std::vector< bodies::BodyPtr > | constraint_region_ |
The constraint region vector. | |
EigenSTL::vector_Isometry3d | constraint_region_pose_ |
The constraint region pose vector. All isometries are guaranteed to be valid. | |
bool | mobile_frame_ |
Whether or not a mobile frame is employed. | |
std::string | constraint_frame_id_ |
The constraint frame id. | |
const moveit::core::LinkModel * | link_model_ |
The link model constraint subject. | |
Protected Attributes inherited from kinematic_constraints::KinematicConstraint | |
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 | |
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 constraints on the XYZ position of a link.
This class expresses X,Y,Z position constraints of a link. The position area is specified as a bounding volume consisting of one or more shapes - either solid primitives or meshes. The pose information in the volumes will be interpreted by using the header information. The header may either specify a fixed frame or a mobile frame. Additionally, a target offset specified in the frame of the link being constrained can be specified. The type value will return POSITION_CONSTRAINT.
Definition at line 533 of file kinematic_constraint.h.
|
inline |
Constructor.
[in] | model | The kinematic model used for constraint evaluation |
Definition at line 544 of file kinematic_constraint.h.
|
overridevirtual |
Clear the stored constraint.
Implements kinematic_constraints::KinematicConstraint.
Definition at line 578 of file kinematic_constraint.cpp.
bool kinematic_constraints::PositionConstraint::configure | ( | const moveit_msgs::msg::PositionConstraint & | pc, |
const moveit::core::Transforms & | tf | ||
) |
Configure the constraint based on a moveit_msgs::msg::PositionConstraint.
For the configure command to be successful, the link must be specified in the model, and one or more constrained regions must be correctly specified, which requires containing a valid shape and a pose for that shape. If the header frame on the constraint is empty, the constraint will fail to configure. If an invalid quaternion is passed for a shape, the identity quaternion will be substituted.
[in] | pc | moveit_msgs::msg::PositionConstraint for configuration |
Definition at line 360 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 522 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 589 of file kinematic_constraint.cpp.
|
overridevirtual |
Check if two constraints are the same. For position constraints this means that:
Two constraint regions matching each other means that:
Note that the two shapes can have different numbers of regions as long as all regions are matched up to another.
[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 462 of file kinematic_constraint.cpp.
|
inline |
Returns all the constraint regions.
Definition at line 639 of file kinematic_constraint.h.
|
inline |
Returns the associated link model, or nullptr if not enabled.
Definition at line 603 of file kinematic_constraint.h.
|
inline |
Returns the target offset.
Definition at line 614 of file kinematic_constraint.h.
|
inline |
Returns the reference frame.
Definition at line 650 of file kinematic_constraint.h.
|
inline |
If the constraint is enabled and the link offset is substantially different than zero.
Definition at line 626 of file kinematic_constraint.h.
|
inline |
If enabled and the specified frame is a mobile frame, return true. Otherwise, returns false.
Definition at line 662 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 566 of file kinematic_constraint.cpp.
|
protected |
The constraint frame id.
Definition at line 676 of file kinematic_constraint.h.
|
protected |
The constraint region vector.
Definition at line 672 of file kinematic_constraint.h.
|
protected |
The constraint region pose vector. All isometries are guaranteed to be valid.
Definition at line 674 of file kinematic_constraint.h.
|
protected |
Whether the offset is substantially different than 0.0.
Definition at line 671 of file kinematic_constraint.h.
|
protected |
The link model constraint subject.
Definition at line 677 of file kinematic_constraint.h.
|
protected |
Whether or not a mobile frame is employed.
Definition at line 675 of file kinematic_constraint.h.
|
protected |
The target offset.
Definition at line 670 of file kinematic_constraint.h.