move_arm_msgs/MoveArmActionResult Message

File: move_arm_msgs/MoveArmActionResult.msg


Header header
actionlib_msgs/GoalStatus status
MoveArmResult result

Expanded Definition

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
MoveArmResult result
    motion_planning_msgs/ArmNavigationErrorCodes error_code
        int32 PLANNING_FAILED=-1
        int32 SUCCESS=1
        int32 TIMED_OUT=-2
        int32 START_STATE_IN_COLLISION=-3
        int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4
        int32 GOAL_IN_COLLISION=-5
        int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6
        int32 INVALID_ROBOT_STATE=-7
        int32 INCOMPLETE_ROBOT_STATE=-8
        int32 INVALID_PLANNER_ID=-9
        int32 INVALID_NUM_PLANNING_ATTEMPTS=-10
        int32 INVALID_ALLOWED_PLANNING_TIME=-11
        int32 INVALID_GROUP_NAME=-12
        int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13
        int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14
        int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15
        int32 INVALID_PATH_JOINT_CONSTRAINTS=-16
        int32 INVALID_PATH_POSITION_CONSTRAINTS=-17
        int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18
        int32 INVALID_TRAJECTORY=-19
        int32 INVALID_INDEX=-20
        int32 JOINT_LIMITS_VIOLATED=-21
        int32 PATH_CONSTRAINTS_VIOLATED=-22
        int32 COLLISION_CONSTRAINTS_VIOLATED=-23
        int32 GOAL_CONSTRAINTS_VIOLATED=-24
        int32 JOINTS_NOT_MOVING=-25
        int32 TRAJECTORY_CONTROLLER_FAILED=-26
        int32 FRAME_TRANSFORM_FAILURE=-27
        int32 COLLISION_CHECKING_UNAVAILABLE=-28
        int32 ROBOT_STATE_STALE=-29
        int32 SENSOR_INFO_STALE=-30
        int32 NO_IK_SOLUTION=-31
        int32 INVALID_LINK_NAME=-32
        int32 IK_LINK_IN_COLLISION=-33
        int32 NO_FK_SOLUTION=-34
        int32 KINEMATICS_STATE_IN_COLLISION=-35
        int32 INVALID_TIMEOUT=-36
        int32 val
    planning_environment_msgs/ContactInformation[] contacts
        uint32 ROBOT_LINK=0
        uint32 OBJECT=1
        uint32 ATTACHED_BODY=2
        Header header
            uint32 seq
            time stamp
            string frame_id
        geometry_msgs/Point position
            float64 x
            float64 y
            float64 z
        geometry_msgs/Vector3 normal
            float64 x
            float64 y
            float64 z
        float64 depth
        string contact_body_1
        string attached_body_1
        uint32 body_type_1
        string contact_body_2
        string attached_body_2
        uint32 body_type_2