object_manipulation_msgs/PlaceAction Message

File: object_manipulation_msgs/PlaceAction.msg


PlaceActionGoal action_goal
PlaceActionResult action_result
PlaceActionFeedback action_feedback

Expanded Definition

PlaceActionGoal action_goal
    Header header
        uint32 seq
        time stamp
        string frame_id
    actionlib_msgs/GoalID goal_id
        time stamp
        string id
    object_manipulation_msgs/PlaceGoal goal
        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
        object_manipulation_msgs/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
        object_manipulation_msgs/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
PlaceActionResult action_result
    Header header
        uint32 seq
        time stamp
        string frame_id
    actionlib_msgs/GoalStatus status
        uint8 PENDING=0
        uint8 ACTIVE=1
        uint8 PREEMPTED=2
        uint8 SUCCEEDED=3
        uint8 ABORTED=4
        uint8 REJECTED=5
        uint8 PREEMPTING=6
        uint8 RECALLING=7
        uint8 RECALLED=8
        uint8 LOST=9
        actionlib_msgs/GoalID goal_id
            time stamp
            string id
        uint8 status
        string text
    object_manipulation_msgs/PlaceResult result
        object_manipulation_msgs/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
        object_manipulation_msgs/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
PlaceActionFeedback action_feedback
    Header header
        uint32 seq
        time stamp
        string frame_id
    actionlib_msgs/GoalStatus status
        uint8 PENDING=0
        uint8 ACTIVE=1
        uint8 PREEMPTED=2
        uint8 SUCCEEDED=3
        uint8 ABORTED=4
        uint8 REJECTED=5
        uint8 PREEMPTING=6
        uint8 RECALLING=7
        uint8 RECALLED=8
        uint8 LOST=9
        actionlib_msgs/GoalID goal_id
            time stamp
            string id
        uint8 status
        string text
    object_manipulation_msgs/PlaceFeedback feedback
        int32 current_location
        int32 total_locations