object_manipulation_msgs/PlaceResult Message

File: object_manipulation_msgs/PlaceResult.msg

# The result of the pickup attempt
ManipulationResult manipulation_result

# The successful place location, if any
geometry_msgs/PoseStamped place_location

# the list of attempted locations, in the order in which they were attempted
# the successful one should be the last one in this list
geometry_msgs/PoseStamped[] attempted_locations

# the outcomes of the attempted locations, in the same order as attempted_locations
PlaceLocationResult[] attempted_location_results

Expanded Definition

ManipulationResult manipulation_result
    int32 SUCCESS=1
    int32 UNFEASIBLE=-1
    int32 FAILED=-2
    int32 ERROR=-3
    int32 ARM_MOVEMENT_PREVENTED=-4
    int32 LIFT_FAILED=-5
    int32 RETREAT_FAILED=-6
    int32 CANCELLED=-7
    int32 value
geometry_msgs/PoseStamped place_location
    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
geometry_msgs/PoseStamped[] attempted_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
PlaceLocationResult[] attempted_location_results
    int32 SUCCESS=1
    int32 PLACE_OUT_OF_REACH=2
    int32 PLACE_IN_COLLISION=3
    int32 PLACE_UNFEASIBLE=4
    int32 PREPLACE_OUT_OF_REACH=5
    int32 PREPLACE_IN_COLLISION=6
    int32 PREPLACE_UNFEASIBLE=7
    int32 RETREAT_OUT_OF_REACH=8
    int32 RETREAT_IN_COLLISION=9
    int32 RETREAT_UNFEASIBLE=10
    int32 MOVE_ARM_FAILED=11
    int32 PLACE_FAILED=12
    int32 RETREAT_FAILED=13
    int32 result_code
    bool continuation_possible