motion_planning_msgs/PositionConstraint Message

File: motion_planning_msgs/PositionConstraint.msg

# This message contains the definition of a position constraint.
Header header

# The robot link this constraint refers to
string link_name

# The offset (in the link frame) for the target point on the link we are planning for
geometry_msgs/Point target_point_offset

# The nominal/target position for the point we are planning for
geometry_msgs/Point position

# The shape of the bounded region that constrains the position of the end-effector
# This region is always centered at the position defined above
geometric_shapes_msgs/Shape constraint_region_shape

# The orientation of the bounded region that constrains the position of the end-effector. 
# This allows the specification of non-axis aligned constraints
geometry_msgs/Quaternion constraint_region_orientation

# Constraint weighting factor - a weight for this constraint
float64 weight

Expanded Definition

Header header
    uint32 seq
    time stamp
    string frame_id
string link_name
geometry_msgs/Point target_point_offset
    float64 x
    float64 y
    float64 z
geometry_msgs/Point position
    float64 x
    float64 y
    float64 z
geometric_shapes_msgs/Shape constraint_region_shape
    byte SPHERE=0
    byte BOX=1
    byte CYLINDER=2
    byte MESH=3
    byte type
    float64[] dimensions
    int32[] triangles
    geometry_msgs/Point[] vertices
        float64 x
        float64 y
        float64 z
geometry_msgs/Quaternion constraint_region_orientation
    float64 x
    float64 y
    float64 z
    float64 w
float64 weight