Public Member Functions | Protected Attributes
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]

List of all members.

Public Member Functions

virtual void clear ()
 Clear the stored constraint.
bool configure (const moveit_msgs::PositionConstraint &pc, const robot_state::Transforms &tf)
 Configure the constraint based on a moveit_msgs::PositionConstraint.
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 constraints are the same. For position constraints this means that:
const std::vector
< bodies::BodyPtr > & 
getConstraintRegions () const
 Returns all the constraint regions.
const robot_model::LinkModelgetLinkModel () const
 Returns the associated link model, or NULL if not enabled.
const Eigen::Vector3d & getLinkOffset () const
 Returns the target offset.
const std::string & getReferenceFrame () const
 Returns the reference frame.
bool hasLinkOffset () const
 If the constraint is enabled and the link offset is substantially different than zero.
bool mobileReferenceFrame () const
 If enabled and the specified frame is a mobile frame, return true. Otherwise, returns false.
 PositionConstraint (const robot_model::RobotModelConstPtr &model)
 Constructor.
virtual void print (std::ostream &out=std::cout) const
 Print the constraint data.
void swapLinkModel (const robot_model::LinkModel *new_link, const Eigen::Affine3d &update)
 Change this constraint to a different link, applying a specified transform to the constraint region. This should be used for links that are associated to each other via fixed transforms.

Protected Attributes

std::string constraint_frame_id_
 The constraint frame id.
std::vector< bodies::BodyPtrconstraint_region_
 The constraint region vector.
EigenSTL::vector_Affine3d constraint_region_pose_
 The constraint region pose vector.
bool has_offset_
 Whether the offset is substantially different than 0.0.
const robot_model::LinkModellink_model_
 The link model constraint subject.
bool mobile_frame_
 Whether or not a mobile frame is employed.
Eigen::Vector3d offset_
 The target offset.

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


Constructor & Destructor Documentation

kinematic_constraints::PositionConstraint::PositionConstraint ( const robot_model::RobotModelConstPtr &  model) [inline]

Constructor.

Parameters:
[in]modelThe kinematic model used for constraint evaluation

Definition at line 520 of file kinematic_constraint.h.


Member Function Documentation

Clear the stored constraint.

Implements kinematic_constraints::KinematicConstraint.

Definition at line 486 of file kinematic_constraint.cpp.

bool kinematic_constraints::PositionConstraint::configure ( const moveit_msgs::PositionConstraint &  pc,
const robot_state::Transforms tf 
)

Configure the constraint based on a moveit_msgs::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::PositionConstraint for configuration
Returns:
True if constraint can be configured from pc

Definition at line 271 of file kinematic_constraint.cpp.

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 442 of file kinematic_constraint.cpp.

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 497 of file kinematic_constraint.cpp.

bool kinematic_constraints::PositionConstraint::equal ( const KinematicConstraint other,
double  margin 
) const [virtual]

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 382 of file kinematic_constraint.cpp.

Returns all the constraint regions.

Returns:
The constraint regions

Definition at line 615 of file kinematic_constraint.h.

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

Returns:
The link model

Definition at line 579 of file kinematic_constraint.h.

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

Returns the target offset.

Returns:
The target offset

Definition at line 590 of file kinematic_constraint.h.

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

Returns the reference frame.

Returns:
The reference frame

Definition at line 626 of file kinematic_constraint.h.

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

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

void kinematic_constraints::PositionConstraint::print ( std::ostream &  out = std::cout) const [virtual]

Print the constraint data.

Parameters:
[in]outThe file descriptor for printing

Reimplemented from kinematic_constraints::KinematicConstraint.

Definition at line 478 of file kinematic_constraint.cpp.

void kinematic_constraints::PositionConstraint::swapLinkModel ( const robot_model::LinkModel new_link,
const Eigen::Affine3d &  update 
)

Change this constraint to a different link, applying a specified transform to the constraint region. This should be used for links that are associated to each other via fixed transforms.

Definition at line 372 of file kinematic_constraint.cpp.


Member Data Documentation

The constraint frame id.

Definition at line 655 of file kinematic_constraint.h.

The constraint region vector.

Definition at line 652 of file kinematic_constraint.h.

The constraint region pose vector.

Definition at line 653 of file kinematic_constraint.h.

Whether the offset is substantially different than 0.0.

Definition at line 651 of file kinematic_constraint.h.

The link model constraint subject.

Definition at line 656 of file kinematic_constraint.h.

Whether or not a mobile frame is employed.

Definition at line 654 of file kinematic_constraint.h.

The target offset.

Definition at line 650 of file kinematic_constraint.h.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Jul 24 2017 02:20:44