object_manipulation_msgs/PlaceGoal Message

File: object_manipulation_msgs/PlaceGoal.msg


# An action for placing an object

# which arm to be used for grasping
string arm_name

# a list of possible desired poses of the object once it's been placed
geometry_msgs/PoseStamped[] place_locations

# the grasp that has been executed on this object
Grasp grasp

# how far the retreat should ideally be away from the place location
float32 desired_retreat_distance

# the min distance between the retreat and the place location that must actually be feasible 
# for the place not to be rejected
float32 min_retreat_distance

# how the place location should be approached
# the frame_id that this lift is specified in MUST be either the robot_frame 
# or the gripper_frame specified in your hand description file
GripperTranslation approach

# the name that the target object has in the collision map
# can be left empty if no name is available
string collision_object_name

# the name that the support surface (e.g. table) has in the collision map
# can be left empty if no name is available
string collision_support_surface_name

# whether collisions between the gripper and the support surface should be acceptable
# during move from pre-place to place and during retreat. Collisions when moving to the
# pre-place location are still not allowed even if this is set to true.
bool allow_gripper_support_collision

# whether reactive placing based on tactile sensors should be used
bool use_reactive_place

# how much the object should be padded by when deciding if the grasp
# location is freasible or not
float64 place_padding

# OPTIONAL (These will not have to be filled out most of the time)
# constraints to be imposed on every point in the motion of the arm
motion_planning_msgs/Constraints path_constraints

# OPTIONAL (These will not have to be filled out most of the time)
# additional collision operations to be used for every arm movement performed
# during placing. Note that these will be added on top of (and thus overide) other 
# collision operations that the grasping pipeline deems necessary. Should be used
# with care and only if special behaviors are desired.
motion_planning_msgs/OrderedCollisionOperations additional_collision_operations

# OPTIONAL (These will not have to be filled out most of the time)
# additional link paddings to be used for every arm movement performed
# during placing. Note that these will be added on top of (and thus overide) other 
# link paddings that the grasping pipeline deems necessary. Should be used
# with care and only if special behaviors are desired.
motion_planning_msgs/LinkPadding[] additional_link_padding

Expanded Definition

string arm_name
geometry_msgs/PoseStamped[] place_locations
    Header header
        uint32 seq
        time stamp
        string frame_id
    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
Grasp grasp
    sensor_msgs/JointState pre_grasp_posture
        Header header
            uint32 seq
            time stamp
            string frame_id
        string[] name
        float64[] position
        float64[] velocity
        float64[] effort
    sensor_msgs/JointState grasp_posture
        Header header
            uint32 seq
            time stamp
            string frame_id
        string[] name
        float64[] position
        float64[] velocity
        float64[] effort
    geometry_msgs/Pose grasp_pose
        geometry_msgs/Point position
            float64 x
            float64 y
            float64 z
        geometry_msgs/Quaternion orientation
            float64 x
            float64 y
            float64 z
            float64 w
    float64 success_probability
    bool cluster_rep
float32 desired_retreat_distance
float32 min_retreat_distance
GripperTranslation approach
    geometry_msgs/Vector3Stamped direction
        Header header
            uint32 seq
            time stamp
            string frame_id
        geometry_msgs/Vector3 vector
            float64 x
            float64 y
            float64 z
    float32 desired_distance
    float32 min_distance
string collision_object_name
string collision_support_surface_name
bool allow_gripper_support_collision
bool use_reactive_place
float64 place_padding
motion_planning_msgs/Constraints path_constraints
    motion_planning_msgs/JointConstraint[] joint_constraints
        string joint_name
        float64 position
        float64 tolerance_above
        float64 tolerance_below
        float64 weight
    motion_planning_msgs/PositionConstraint[] position_constraints
        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
    motion_planning_msgs/OrientationConstraint[] orientation_constraints
        int32 LINK_FRAME=0
        int32 HEADER_FRAME=1
        Header header
            uint32 seq
            time stamp
            string frame_id
        string link_name
        int32 type
        geometry_msgs/Quaternion orientation
            float64 x
            float64 y
            float64 z
            float64 w
        float64 absolute_roll_tolerance
        float64 absolute_pitch_tolerance
        float64 absolute_yaw_tolerance
        float64 weight
    motion_planning_msgs/VisibilityConstraint[] visibility_constraints
        Header header
            uint32 seq
            time stamp
            string frame_id
        geometry_msgs/PointStamped target
            Header header
                uint32 seq
                time stamp
                string frame_id
            geometry_msgs/Point point
                float64 x
                float64 y
                float64 z
        geometry_msgs/PoseStamped sensor_pose
            Header header
                uint32 seq
                time stamp
                string frame_id
            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
        float64 absolute_tolerance
motion_planning_msgs/OrderedCollisionOperations additional_collision_operations
    motion_planning_msgs/CollisionOperation[] collision_operations
        string COLLISION_SET_ALL="all"
        string COLLISION_SET_OBJECTS="objects"
        string COLLISION_SET_ATTACHED_OBJECTS="attached"
        int32 DISABLE=0
        int32 ENABLE=1
        string object1
        string object2
        float64 penetration_distance
        int32 operation
motion_planning_msgs/LinkPadding[] additional_link_padding
    string link_name
    float64 padding