diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml
index f453ddf419..36edd70fc6 100644
--- a/message_definitions/v1.0/common.xml
+++ b/message_definitions/v1.0/common.xml
@@ -311,6 +311,21 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
@@ -1376,18 +1391,18 @@
WIP: Request camera information (CAMERA_INFORMATION).
- Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
+ Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)
0: No action 1: Request camera capabilities
Reserved (all remaining params)
- WIP: Request camera settings (CAMERA_SETTINGS)
- Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
+ WIP: Request camera settings (CAMERA_SETTINGS).
+ Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)
0: No Action 1: Request camera settings
Reserved (all remaining params)
- WIP: Set the camera settings part 1 (CAMERA_SETTINGS). Use NAN for reserved values and values you don't want to change.
+ WIP: Set the camera settings part 1 (CAMERA_SETTINGS). Use NAN for reserved values and values you don't want to change. (EXPERIMENTAL: IT WILL BE REMOVED)
Camera ID (1 for first, 2 for second, etc.)
Aperture (1/value)
Shutter speed in seconds
@@ -1397,7 +1412,7 @@
White balance (color temperature in K) (0: Auto WB, -1: Lock at current auto value)
- WIP: Set the camera settings part 2 (CAMERA_SETTINGS). Use NAN for reserved values and values you don't want to change.
+ WIP: Set the camera settings part 2 (CAMERA_SETTINGS). Use NAN for reserved values and values you don't want to change. (EXPERIMENTAL: IT WILL BE REMOVED)
Camera ID (1 for first, 2 for second, etc.)
Reserved for Flicker mode (0 for Auto)
Reserved for metering mode ID (Average, Center, Spot, etc.)
@@ -1420,7 +1435,7 @@
WIP: Request camera capture status (CAMERA_CAPTURE_STATUS)
- Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
+ Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)
0: No Action 1: Request camera capture status
Reserved (all remaining params)
@@ -1431,19 +1446,18 @@
WIP: Reset all camera settings to Factory Default (CAMERA_SETTINGS)
- Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
+ Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)
0: No Action 1: Reset all settings
Reserved (all remaining params)
WIP: Set camera running mode. Use NAN for reserved values and values you don't want to change.
- Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
- Camera mode (0: photo mode, 1: video mode)
- Audio recording enabled (0: off 1: on)
- Reserved (all remaining params)
+ Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)
+ Camera mode (0: photo/image mode, 1: video mode)
+ Reserved (all remaining params)
- WIP: Set the camera settings part 3 (CAMERA_SETTINGS). Use NAN for reserved values and values you don't want to change.
+ WIP: Set the camera settings part 3 (CAMERA_SETTINGS). Use NAN for reserved values and values you don't want to change. (EXPERIMENTAL: IT WILL BE REMOVED)
Camera ID (1 for first, 2 for second, etc.)
Photo resolution ID (4000x3000, 2560x1920, etc., -1 for maximum possible)
Video resolution and rate ID (4K 60 Hz, 4K 30 Hz, HD 60 Hz, HD 30 Hz, etc., -1 for maximum possible)
@@ -1451,19 +1465,19 @@
WIP: Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. Use NAN for reserved values.
- Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
+ Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)
Duration between two consecutive pictures (in seconds)
Number of images to capture total - 0 for unlimited capture
Reserved
WIP: Stop image capture sequence
- Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
+ Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)
Reserved
WIP: Re-request a CAMERA_IMAGE_CAPTURE packet. Use NAN for reserved values.
- Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
+ Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)
Sequence number for missing CAMERA_IMAGE_CAPTURE packet
Reserved (all remaining params)
@@ -1475,13 +1489,13 @@
WIP: Starts video capture (recording). Use NAN for reserved values.
- Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
+ Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)
Frequency CAMERA_CAPTURE_STATUS messages should be sent while recording (0 for no messages, otherwise frequency in Hz)
Reserved
WIP: Stop the current video capture (recording). Use NAN for reserved values.
- Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
+ Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)
Reserved
@@ -2589,6 +2603,24 @@
Landing target represented by a pre-defined visual shape/feature (ex: X-marker, H-marker, square)
+
+ Camera capability flags (Bitmap).
+
+ Camera is able to record video.
+
+
+ Camera is able to capture images.
+
+
+ Camera has separate Video and Image/Photo modes (MAV_CMD_SET_CAMERA_MODE)
+
+
+ Camera can capture images while in video mode
+
+
+ Camera can capture videos while in Photo/Image mode
+
+
Result from a PARAM_EXT_SET message.
@@ -4092,37 +4124,40 @@
WIP: Information about a camera
Timestamp (milliseconds since system boot)
- Camera ID (1 for first, 2 for second, etc.)
- Number of cameras
+ Camera ID (1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)
+ Number of cameras (EXPERIMENTAL: IT WILL BE REMOVED)
Name of the camera vendor
Name of the camera model
- Version of the camera firmware
+ Version of the camera firmware (v << 24 & 0xff = Dev, v << 16 & 0xff = Patch, v << 8 & 0xff = Minor, v & 0xff = Major)
Focal length in mm
Image sensor size horizontal in mm
Image sensor size vertical in mm
Image resolution in pixels horizontal
Image resolution in pixels vertical
Reserved for a lens ID
+ CAMERA_CAP_FLAGS enum flags (bitmap) describing camera capabilities.
+ Camera definition version (iteration)
+ Camera definition URI (if any, otherwise only basic functions will be available).
- WIP: Settings of a camera, can be requested using MAV_CMD_REQUEST_CAMERA_SETTINGS and written using MAV_CMD_SET_CAMERA_SETTINGS
+ WIP: Settings of a camera, can be requested using MAV_CMD_REQUEST_CAMERA_SETTINGS and written using MAV_CMD_SET_CAMERA_SETTINGS.
Timestamp (milliseconds since system boot)
- Camera ID (1 for first, 2 for second, etc.)
- 0: full auto 1: full manual 2: aperture priority 3: shutter priority
- Aperture is 1/value
- Shutter speed in seconds
- ISO sensitivity
- Exposure Value
- Color temperature in degrees Kelvin. (0: Auto WB, -1: Locked at auto value)
- Reserved for a camera mode ID. (0: Photo 1: Video)
- Audio recording enabled (0: off 1: on)
- Reserved for a color mode ID (Neutral, Vivid, etc.)
- Reserved for image format ID (Jpeg/Raw/Jpeg+Raw)
- Reserved for image quality ID (Compression)
- Reserved for metering mode ID (Average, Center, Spot, etc.)
- Reserved for flicker mode ID (Auto, 60Hz, 50Hz, etc.)
- Photo resolution ID (4000x3000, 2560x1920, etc.)
- Video resolution and rate ID (4K 60 Hz, 4K 30 Hz, HD 60 Hz, HD 30 Hz, etc.)
+ Camera ID (1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)
+ 0: full auto 1: full manual 2: aperture priority 3: shutter priority. (EXPERIMENTAL: IT WILL BE REMOVED)
+ Aperture is 1/value. (EXPERIMENTAL: IT WILL BE REMOVED)
+ Shutter speed in seconds. (EXPERIMENTAL: IT WILL BE REMOVED)
+ ISO sensitivity. (EXPERIMENTAL: IT WILL BE REMOVED)
+ Exposure Value. (EXPERIMENTAL: IT WILL BE REMOVED)
+ Color temperature in degrees Kelvin. (0: Auto WB, -1: Locked at auto value). (EXPERIMENTAL: IT WILL BE REMOVED)
+ Camera mode ID (0: Photo 1: Video)
+ Audio recording enabled (0: off 1: on). (EXPERIMENTAL: IT WILL BE REMOVED)
+ Reserved for a color mode ID (Neutral, Vivid, etc.). (EXPERIMENTAL: IT WILL BE REMOVED)
+ Reserved for image format ID (Jpeg/Raw/Jpeg+Raw). (EXPERIMENTAL: IT WILL BE REMOVED)
+ Reserved for image quality ID (Compression). (EXPERIMENTAL: IT WILL BE REMOVED)
+ Reserved for metering mode ID (Average, Center, Spot, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)
+ Reserved for flicker mode ID (Auto, 60Hz, 50Hz, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)
+ Photo resolution ID (4000x3000, 2560x1920, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)
+ Video resolution and rate ID (4K 60 Hz, 4K 30 Hz, HD 60 Hz, HD 30 Hz, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)
WIP: Information about a storage medium.
@@ -4150,7 +4185,7 @@
WIP: Information about a captured image
Timestamp (milliseconds since system boot)
Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown.
- Camera ID (1 for first, 2 for second, etc.)
+ Camera ID (1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)
Latitude, expressed as degrees * 1E7 where image was taken
Longitude, expressed as degrees * 1E7 where capture was taken
Altitude in meters, expressed as * 1E3 (AMSL, not WGS84) where image was taken