motion_planning_msgs/SimplePoseConstraint Message

File: motion_planning_msgs/SimplePoseConstraint.msg

# This message contains the definition of a simple pose constraint 
# that specifies the pose for a particular link of the robot and corresponding
# (absolute) position and orientation tolerances

# The standard ROS message header
Header header

# The robot link this constraint refers to
string link_name

# The desired position of the robot link
geometry_msgs/Pose pose

# Position (absolute) tolerance
geometry_msgs/Point absolute_position_tolerance

# Orientation (absolute) tolerance
float64 absolute_roll_tolerance
float64 absolute_yaw_tolerance
float64 absolute_pitch_tolerance

int32 orientation_constraint_type
int32 HEADER_FRAME=0
int32 LINK_FRAME=1

Expanded Definition

int32 HEADER_FRAME=0
int32 LINK_FRAME=1
Header header
    uint32 seq
    time stamp
    string frame_id
string link_name
geometry_msgs/Pose pose
    geometry_msgs/Point position
        float64 x
        float64 y
        float64 z
    geometry_msgs/Quaternion orientation
        float64 x
        float64 y
        float64 z
        float64 w
geometry_msgs/Point absolute_position_tolerance
    float64 x
    float64 y
    float64 z
float64 absolute_roll_tolerance
float64 absolute_yaw_tolerance
float64 absolute_pitch_tolerance
int32 orientation_constraint_type