object_recognition_gui/ObjectRecognitionGuiActionGoal Message

File: object_recognition_gui/ObjectRecognitionGuiActionGoal.msg

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

Header header
actionlib_msgs/GoalID goal_id
ObjectRecognitionGuiGoal goal

Expanded Definition

Header header
    uint32 seq
    time stamp
    string frame_id
actionlib_msgs/GoalID goal_id
    time stamp
    string id
ObjectRecognitionGuiGoal goal
    sensor_msgs/Image image
        Header header
            uint32 seq
            time stamp
            string frame_id
        uint32 height
        uint32 width
        string encoding
        uint8 is_bigendian
        uint32 step
        uint8[] data
    sensor_msgs/CameraInfo camera_info
        Header header
            uint32 seq
            time stamp
            string frame_id
        uint32 height
        uint32 width
        string distortion_model
        float64[] D
        float64[9] K
        float64[9] R
        float64[12] P
        uint32 binning_x
        uint32 binning_y
        sensor_msgs/RegionOfInterest roi
            uint32 x_offset
            uint32 y_offset
            uint32 height
            uint32 width
            bool do_rectify
    object_recognition_gui/ModelHypothesisList[] model_hypotheses
        object_recognition_gui/ModelHypothesis[] hypotheses
            geometric_shapes_msgs/Shape mesh
                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/PoseStamped 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
        bool accept