calibration_msgs/CameraMeasurement Message

File: calibration_msgs/CameraMeasurement.msg

Header header
string camera_id
ImagePoint[] image_points
sensor_msgs/CameraInfo cam_info

# True -> The extra debugging fields are populated
bool verbose

# Extra, partially processed data. Only needed for debugging
sensor_msgs/Image image
sensor_msgs/Image image_rect
calibration_msgs/CalibrationPattern features

Expanded Definition

Header header
    uint32 seq
    time stamp
    string frame_id
string camera_id
ImagePoint[] image_points
    float32 x
    float32 y
sensor_msgs/CameraInfo cam_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
bool verbose
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/Image image_rect
    Header header
        uint32 seq
        time stamp
        string frame_id
    uint32 height
    uint32 width
    string encoding
    uint8 is_bigendian
    uint32 step
    uint8[] data
calibration_msgs/CalibrationPattern features
    Header header
        uint32 seq
        time stamp
        string frame_id
    geometry_msgs/Point32[] object_points
        float32 x
        float32 y
        float32 z
    calibration_msgs/ImagePoint[] image_points
        float32 x
        float32 y
    uint8 success