object_manipulation_msgs/ReactivePlaceAction Message

File: object_manipulation_msgs/ReactivePlaceAction.msg

# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======

ReactivePlaceActionGoal action_goal
ReactivePlaceActionResult action_result
ReactivePlaceActionFeedback action_feedback

Expanded Definition

ReactivePlaceActionGoal action_goal
    Header header
        uint32 seq
        time stamp
        string frame_id
    actionlib_msgs/GoalID goal_id
        time stamp
        string id
    object_manipulation_msgs/ReactivePlaceGoal goal
        string arm_name
        geometry_msgs/PoseStamped final_place_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
        trajectory_msgs/JointTrajectory trajectory
            Header header
                uint32 seq
                time stamp
                string frame_id
            string[] joint_names
            trajectory_msgs/JointTrajectoryPoint[] points
                float64[] positions
                float64[] velocities
                float64[] accelerations
                duration time_from_start
        string collision_support_surface_name
        string collision_object_name
ReactivePlaceActionResult 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/ReactivePlaceResult 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
ReactivePlaceActionFeedback 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/ReactivePlaceFeedback feedback
        object_manipulation_msgs/ManipulationPhase manipulation_phase
            int32 CHECKING_FEASIBILITY=0
            int32 MOVING_TO_PREGRASP=1
            int32 MOVING_TO_GRASP=2
            int32 CLOSING=3
            int32 ADJUSTING_GRASP=4
            int32 LIFTING=5
            int32 MOVING_WITH_OBJECT=6
            int32 MOVING_TO_PLACE=7
            int32 PLACING=8
            int32 OPENING=9
            int32 RETREATING=10
            int32 MOVING_WITHOUT_OBJECT=11
            int32 SHAKING=12
            int32 SUCCEEDED=13
            int32 FAILED=14
            int32 ABORTED=15
            int32 HOLDING_OBJECT=16
            int32 phase