moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Protected Attributes | List of all members
kinematic_constraints::PositionConstraint Class Reference

Class for constraints on the XYZ position of a link. More...

#include <kinematic_constraint.h>

Inheritance diagram for kinematic_constraints::PositionConstraint:
Inheritance graph
[legend]
Collaboration diagram for kinematic_constraints::PositionConstraint:
Collaboration graph
[legend]

Public Member Functions

 PositionConstraint (const moveit::core::RobotModelConstPtr &model)
 Constructor. More...
 
bool configure (const moveit_msgs::msg::PositionConstraint &pc, const moveit::core::Transforms &tf)
 Configure the constraint based on a moveit_msgs::msg::PositionConstraint. More...
 
bool equal (const KinematicConstraint &other, double margin) const override
 Check if two constraints are the same. For position constraints this means that: More...
 
void clear () override
 Clear the stored constraint. 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...
 
void print (std::ostream &out=std::cout) const override
 Print the constraint data. More...
 
const moveit::core::LinkModelgetLinkModel () const
 Returns the associated link model, or nullptr if not enabled. More...
 
const Eigen::Vector3d & getLinkOffset () const
 Returns the target offset. More...
 
bool hasLinkOffset () const
 If the constraint is enabled and the link offset is substantially different than zero. More...
 
const std::vector< bodies::BodyPtr > & getConstraintRegions () const
 Returns all the constraint regions. More...
 
const std::string & getReferenceFrame () const
 Returns the reference frame. More...
 
bool mobileReferenceFrame () const
 If enabled and the specified frame is a mobile frame, return true. Otherwise, returns false. More...
 
- Public Member Functions inherited from kinematic_constraints::KinematicConstraint
 KinematicConstraint (const moveit::core::RobotModelConstPtr &model)
 Constructor. More...
 
virtual ~KinematicConstraint ()
 
ConstraintType getType () const
 Get the type of constraint. More...
 
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
 

Protected Attributes

Eigen::Vector3d offset_
 The target offset. More...
 
bool has_offset_
 Whether the offset is substantially different than 0.0. More...
 
std::vector< bodies::BodyPtr > constraint_region_
 The constraint region vector. More...
 
EigenSTL::vector_Isometry3d constraint_region_pose_
 The constraint region pose vector. All isometries are guaranteed to be valid. More...
 
bool mobile_frame_
 Whether or not a mobile frame is employed. More...
 
std::string constraint_frame_id_
 The constraint frame id. More...
 
const moveit::core::LinkModellink_model_
 The link model constraint subject. More...
 
- Protected Attributes inherited from kinematic_constraints::KinematicConstraint
ConstraintType type_
 The type of the constraint. More...
 
moveit::core::RobotModelConstPtr robot_model_
 The kinematic model associated with this constraint. More...
 
double constraint_weight_
 The weight of a constraint is a multiplicative factor associated to the distance computed by the decide() function
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...
 

Detailed Description

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 514 of file kinematic_constraint.h.

Constructor & Destructor Documentation

◆ PositionConstraint()

kinematic_constraints::PositionConstraint::PositionConstraint ( const moveit::core::RobotModelConstPtr &  model)
inline

Constructor.

Parameters
[in]modelThe kinematic model used for constraint evaluation

Definition at line 525 of file kinematic_constraint.h.

Member Function Documentation

◆ clear()

void kinematic_constraints::PositionConstraint::clear ( )
overridevirtual

Clear the stored constraint.

Implements kinematic_constraints::KinematicConstraint.

Definition at line 542 of file kinematic_constraint.cpp.

Here is the caller graph for this function:

◆ configure()

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.

Parameters
[in]pcmoveit_msgs::msg::PositionConstraint for configuration
Returns
True if constraint can be configured from pc

Definition at line 338 of file kinematic_constraint.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ decide()

ConstraintEvaluationResult kinematic_constraints::PositionConstraint::decide ( const moveit::core::RobotState state,
bool  verbose = false 
) const
overridevirtual

Decide whether the constraint is satisfied in the indicated state.

Parameters
[in]stateThe kinematic state used for evaluation
[in]verboseWhether or not to print output
Returns

Implements kinematic_constraints::KinematicConstraint.

Definition at line 498 of file kinematic_constraint.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ enabled()

bool kinematic_constraints::PositionConstraint::enabled ( ) const
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 553 of file kinematic_constraint.cpp.

Here is the caller graph for this function:

◆ equal()

bool kinematic_constraints::PositionConstraint::equal ( const KinematicConstraint other,
double  margin 
) const
overridevirtual

Check if two constraints are the same. For position constraints this means that:

  • The types are the same
  • The link model is the same
  • The frame of the constraints are the same
  • The target offsets are no more than the margin apart
  • Each entry in the constraint region of this constraint matches a region in the other constraint
  • Each entry in the other constraint region matches a region in the other constraint

Two constraint regions matching each other means that:

  • The poses match within the margin
  • The types are the same
  • The shape volumes are within the margin

Note that the two shapes can have different numbers of regions as long as all regions are matched up to another.

Parameters
[in]otherThe other constraint to test
[in]marginThe margin to apply to all values associated with constraint
Returns
True if equal, otherwise false

Implements kinematic_constraints::KinematicConstraint.

Definition at line 440 of file kinematic_constraint.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getConstraintRegions()

const std::vector<bodies::BodyPtr>& kinematic_constraints::PositionConstraint::getConstraintRegions ( ) const
inline

Returns all the constraint regions.

Returns
The constraint regions

Definition at line 620 of file kinematic_constraint.h.

◆ getLinkModel()

const moveit::core::LinkModel* kinematic_constraints::PositionConstraint::getLinkModel ( ) const
inline

Returns the associated link model, or nullptr if not enabled.

Returns
The link model

Definition at line 584 of file kinematic_constraint.h.

◆ getLinkOffset()

const Eigen::Vector3d& kinematic_constraints::PositionConstraint::getLinkOffset ( ) const
inline

Returns the target offset.

Returns
The target offset

Definition at line 595 of file kinematic_constraint.h.

◆ getReferenceFrame()

const std::string& kinematic_constraints::PositionConstraint::getReferenceFrame ( ) const
inline

Returns the reference frame.

Returns
The reference frame

Definition at line 631 of file kinematic_constraint.h.

◆ hasLinkOffset()

bool kinematic_constraints::PositionConstraint::hasLinkOffset ( ) const
inline

If the constraint is enabled and the link offset is substantially different than zero.

Returns
Whether or not there is a link offset

Definition at line 607 of file kinematic_constraint.h.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ mobileReferenceFrame()

bool kinematic_constraints::PositionConstraint::mobileReferenceFrame ( ) const
inline

If enabled and the specified frame is a mobile frame, return true. Otherwise, returns false.

Returns
Whether a mobile reference frame is being employed

Definition at line 643 of file kinematic_constraint.h.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ print()

void kinematic_constraints::PositionConstraint::print ( std::ostream &  = std::cout) const
overridevirtual

Print the constraint data.

Parameters
[in]outThe file descriptor for printing

Reimplemented from kinematic_constraints::KinematicConstraint.

Definition at line 534 of file kinematic_constraint.cpp.

Here is the call graph for this function:

Member Data Documentation

◆ constraint_frame_id_

std::string kinematic_constraints::PositionConstraint::constraint_frame_id_
protected

The constraint frame id.

Definition at line 657 of file kinematic_constraint.h.

◆ constraint_region_

std::vector<bodies::BodyPtr> kinematic_constraints::PositionConstraint::constraint_region_
protected

The constraint region vector.

Definition at line 653 of file kinematic_constraint.h.

◆ constraint_region_pose_

EigenSTL::vector_Isometry3d kinematic_constraints::PositionConstraint::constraint_region_pose_
protected

The constraint region pose vector. All isometries are guaranteed to be valid.

Definition at line 655 of file kinematic_constraint.h.

◆ has_offset_

bool kinematic_constraints::PositionConstraint::has_offset_
protected

Whether the offset is substantially different than 0.0.

Definition at line 652 of file kinematic_constraint.h.

◆ link_model_

const moveit::core::LinkModel* kinematic_constraints::PositionConstraint::link_model_
protected

The link model constraint subject.

Definition at line 658 of file kinematic_constraint.h.

◆ mobile_frame_

bool kinematic_constraints::PositionConstraint::mobile_frame_
protected

Whether or not a mobile frame is employed.

Definition at line 656 of file kinematic_constraint.h.

◆ offset_

Eigen::Vector3d kinematic_constraints::PositionConstraint::offset_
protected

The target offset.

Definition at line 651 of file kinematic_constraint.h.


The documentation for this class was generated from the following files: