MAVLink Camera API Discussion

And these are the messages:

CAMERA_INFORMATION ( #259 )
WIP: Information about a camera

Field Name          Type        Description
time_boot_ms        uint32_t    Timestamp (milliseconds since system boot)
camera_id           uint8_t     Camera ID (1 for first, 2 for second, etc.)
camera_count        uint8_t     Number of cameras
vendor_name         uint8_t[32] Name of the camera vendor
model_name          uint8_t[32] Name of the camera model
firmware_version    uint32_t    Version of the camera firmware
focal_length        float       Focal length in mm
sensor_size_h       float       Image sensor size horizontal in mm
sensor_size_v       float       Image sensor size vertical in mm
resolution_h        uint16_t    Image resolution in pixels horizontal
resolution_v        uint16_t    Image resolution in pixels vertical
lens_id             uint8_t     Reserved for a lens ID

CAMERA_SETTINGS ( #260 )
WIP: Settings of a camera, can be requested using MAV_CMD_REQUEST_CAMERA_SETTINGS and written using MAV_CMD_SET_CAMERA_SETTINGS

Field Name          Type        Description
time_boot_ms        uint32_t    Timestamp (milliseconds since system boot)
camera_id           uint8_t     Camera ID (1 for first, 2 for second, etc.)
exposure_mode       uint8_t     0: full auto 1: full manual 2: aperture priority 3: shutter priority
aperture            float       Aperture is 1/value
shutter_speed       float       Shutter speed in seconds
iso_sensitivity     float       ISO sensitivity
ev                  float       Exposure Value
white_balance       float       Color temperature in degrees Kelvin. (0: Auto WB)
mode_id             uint8_t     Reserved for a camera mode ID. (0: Photo 1: Video)
audio_recording     uint8_t     Audio recording enabled (0: off 1: on)
color_mode_id       uint8_t     Reserved for a color mode ID (Neutral, Vivid, etc.)
image_format_id     uint8_t     Reserved for image format ID (Jpeg/Raw/Jpeg+Raw)
image_quality_id    uint8_t     Reserved for image quality ID (Compression)
metering_mode_id    uint8_t     Reserved for metering mode ID (Average, Center, Spot, etc.)
flicker_mode_id     uint8_t     Reserved for flicker mode ID (Auto, 60Hz, 50Hz, etc.)

STORAGE_INFORMATION ( #261 )
WIP: Information about a storage medium

Field Name          Type        Description
time_boot_ms        uint32_t    Timestamp (milliseconds since system boot)
storage_id          uint8_t     Storage ID (1 for first, 2 for second, etc.)
storage_count       uint8_t     Number of storage devices
status              uint8_t     Status of storage (0 not available, 1 unformatted, 2 formatted)
total_capacity      float       Total capacity in MiB
used_capacity       float       Used capacity in MiB
available_capacity  float       Available capacity in MiB
read_speed          float       Read speed in MiB/s
write_speed         float       Write speed in MiB/s

CAMERA_CAPTURE_STATUS ( #262 )
WIP: Information about the status of a capture

Field Name          Type        Description
time_boot_ms        uint32_t    Timestamp (milliseconds since system boot)
camera_id           uint8_t     Camera ID (1 for first, 2 for second, etc.)
image_status        uint8_t     Current status of image capturing (0: not running, 1: interval capture in progress)
video_status        uint8_t     Current status of video capturing (0: not running, 1: capture in progress)
image_interval      float       Image capture interval in seconds
video_framerate     float       Video frame rate in Hz
image_resolution_h  uint16_t    Image resolution in pixels horizontal
image_resolution_v  uint16_t    Image resolution in pixels vertical
video_resolution_h  uint16_t    Video resolution in pixels horizontal
video_resolution_v  uint16_t    Video resolution in pixels vertical
recording_time_ms   uint32_t    Time in milliseconds since recording started
available_capacity  float       Available storage capacity in MiB

CAMERA_IMAGE_CAPTURED ( #263 )
WIP: Information about a captured image

Field Name          Type        Description
time_boot_ms        uint32_t    Timestamp (milliseconds since system boot)
time_utc            uint64_t    Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown.
camera_id           uint8_t     Camera ID (1 for first, 2 for second, etc.)
lat                 int32_t     Latitude, expressed as degrees * 1E7 where image was taken
lon                 int32_t     Longitude, expressed as degrees * 1E7 where capture was taken
alt                 int32_t     Altitude in meters, expressed as * 1E3 (AMSL, not WGS84) where image was taken
relative_alt        int32_t     Altitude above ground in meters, expressed as * 1E3 where image was taken
q                   float[4]    Quaternion of camera orientation (w, x, y, z order, zero-rotation is 0, 0, 0, 0)
image_index         int32_t     Zero based index of this image (image count since armed -1)
capture_result      int8_t      Boolean indicating success (1) or failure (0) while capturing this image.
file_url            char[205]   URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.

VIDEO_STREAM_INFORMATION ( #269 )
WIP: Information about video stream

Field Name          Type        Description
camera_id           uint8_t     Camera ID (1 for first, 2 for second, etc.)
status              uint8_t     Current status of video streaming (0: not running, 1: in progress)
framerate           float       Frames per second
resolution_h        uint16_t    Resolution horizontal in pixels
resolution_v        uint16_t    Resolution vertical in pixels
bitrate             uint32_t    Bit rate in bits per second
rotation            uint16_t    Video image rotation clockwise
uri                 char[230]   Video stream URI


SET_VIDEO_STREAM_SETTINGS ( #270 )
WIP: Message that sets video stream settings

Field Name          Type        Description
target_system       uint8_t     system ID of the target
target_component    uint8_t     component ID of the target
camera_id           uint8_t     Camera ID (1 for first, 2 for second, etc.)
framerate           float       Frames per second (set to -1 for highest framerate possible)
resolution_h        uint16_t    Resolution horizontal in pixels (set to -1 for highest resolution possible)
resolution_v        uint16_t    Resolution vertical in pixels (set to -1 for highest resolution possible)
bitrate             uint32_t    Bit rate in bits per second (set to -1 for auto)
rotation            uint16_t    Video image rotation clockwise (0-359 degrees)
uri                 char[230]   Video stream URI