Skip to content

Commit

Permalink
Camera Definition (#747)
Browse files Browse the repository at this point in the history
* Preparing for camera definition

* Removing Camera ID (flagging it as to be removed)
Rename Photo to Image where appropriate
Remove device_id from COMMAND_ACK

* Reserving space for 6 cameras.
  • Loading branch information
dogmaphobic authored and LorenzMeier committed Jul 15, 2017
1 parent 3e879e7 commit e722542
Showing 1 changed file with 73 additions and 38 deletions.
111 changes: 73 additions & 38 deletions message_definitions/v1.0/common.xml
Expand Up @@ -311,6 +311,21 @@
<entry value="100" name="MAV_COMP_ID_CAMERA">
<description/>
</entry>
<entry value="101" name="MAV_COMP_ID_CAMERA2">
<description/>
</entry>
<entry value="102" name="MAV_COMP_ID_CAMERA3">
<description/>
</entry>
<entry value="103" name="MAV_COMP_ID_CAMERA4">
<description/>
</entry>
<entry value="104" name="MAV_COMP_ID_CAMERA5">
<description/>
</entry>
<entry value="105" name="MAV_COMP_ID_CAMERA6">
<description/>
</entry>
<entry value="140" name="MAV_COMP_ID_SERVO1">
<description/>
</entry>
Expand Down Expand Up @@ -1376,18 +1391,18 @@
</entry>
<entry value="521" name="MAV_CMD_REQUEST_CAMERA_INFORMATION">
<description>WIP: Request camera information (CAMERA_INFORMATION).</description>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)</param>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)</param>
<param index="2">0: No action 1: Request camera capabilities</param>
<param index="3">Reserved (all remaining params)</param>
</entry>
<entry value="522" name="MAV_CMD_REQUEST_CAMERA_SETTINGS">
<description>WIP: Request camera settings (CAMERA_SETTINGS)</description>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)</param>
<description>WIP: Request camera settings (CAMERA_SETTINGS).</description>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)</param>
<param index="2">0: No Action 1: Request camera settings</param>
<param index="3">Reserved (all remaining params)</param>
</entry>
<entry value="523" name="MAV_CMD_SET_CAMERA_SETTINGS_1">
<description>WIP: Set the camera settings part 1 (CAMERA_SETTINGS). Use NAN for reserved values and values you don't want to change.</description>
<description>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)</description>
<param index="1">Camera ID (1 for first, 2 for second, etc.)</param>
<param index="2">Aperture (1/value)</param>
<param index="3">Shutter speed in seconds</param>
Expand All @@ -1397,7 +1412,7 @@
<param index="7">White balance (color temperature in K) (0: Auto WB, -1: Lock at current auto value)</param>
</entry>
<entry value="524" name="MAV_CMD_SET_CAMERA_SETTINGS_2">
<description>WIP: Set the camera settings part 2 (CAMERA_SETTINGS). Use NAN for reserved values and values you don't want to change.</description>
<description>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)</description>
<param index="1">Camera ID (1 for first, 2 for second, etc.)</param>
<param index="2">Reserved for Flicker mode (0 for Auto)</param>
<param index="3">Reserved for metering mode ID (Average, Center, Spot, etc.)</param>
Expand All @@ -1420,7 +1435,7 @@
</entry>
<entry value="527" name="MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS">
<description>WIP: Request camera capture status (CAMERA_CAPTURE_STATUS)</description>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)</param>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)</param>
<param index="2">0: No Action 1: Request camera capture status</param>
<param index="3">Reserved (all remaining params)</param>
</entry>
Expand All @@ -1431,39 +1446,38 @@
</entry>
<entry value="529" name="MAV_CMD_RESET_CAMERA_SETTINGS">
<description>WIP: Reset all camera settings to Factory Default (CAMERA_SETTINGS)</description>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)</param>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)</param>
<param index="2">0: No Action 1: Reset all settings</param>
<param index="3">Reserved (all remaining params)</param>
</entry>
<entry value="530" name="MAV_CMD_SET_CAMERA_MODE">
<description>WIP: Set camera running mode. Use NAN for reserved values and values you don't want to change.</description>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)</param>
<param index="2">Camera mode (0: photo mode, 1: video mode)</param>
<param index="3">Audio recording enabled (0: off 1: on)</param>
<param index="4">Reserved (all remaining params)</param>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)</param>
<param index="2">Camera mode (0: photo/image mode, 1: video mode)</param>
<param index="3">Reserved (all remaining params)</param>
</entry>
<entry value="531" name="MAV_CMD_SET_CAMERA_SETTINGS_3">
<description>WIP: Set the camera settings part 3 (CAMERA_SETTINGS). Use NAN for reserved values and values you don't want to change.</description>
<description>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)</description>
<param index="1">Camera ID (1 for first, 2 for second, etc.)</param>
<param index="2">Photo resolution ID (4000x3000, 2560x1920, etc., -1 for maximum possible)</param>
<param index="3">Video resolution and rate ID (4K 60 Hz, 4K 30 Hz, HD 60 Hz, HD 30 Hz, etc., -1 for maximum possible)</param>
<param index="4">Reserved (all remaining params)</param>
</entry>
<entry value="2000" name="MAV_CMD_IMAGE_START_CAPTURE">
<description>WIP: Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. Use NAN for reserved values.</description>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)</param>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)</param>
<param index="2">Duration between two consecutive pictures (in seconds)</param>
<param index="3">Number of images to capture total - 0 for unlimited capture</param>
<param index="4">Reserved</param>
</entry>
<entry value="2001" name="MAV_CMD_IMAGE_STOP_CAPTURE">
<description>WIP: Stop image capture sequence</description>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)</param>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)</param>
<param index="2">Reserved</param>
</entry>
<entry value="2002" name="MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE">
<description>WIP: Re-request a CAMERA_IMAGE_CAPTURE packet. Use NAN for reserved values.</description>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)</param>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)</param>
<param index="2">Sequence number for missing CAMERA_IMAGE_CAPTURE packet</param>
<param index="3">Reserved (all remaining params)</param>
</entry>
Expand All @@ -1475,13 +1489,13 @@
</entry>
<entry value="2500" name="MAV_CMD_VIDEO_START_CAPTURE">
<description>WIP: Starts video capture (recording). Use NAN for reserved values.</description>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)</param>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)</param>
<param index="2">Frequency CAMERA_CAPTURE_STATUS messages should be sent while recording (0 for no messages, otherwise frequency in Hz)</param>
<param index="3">Reserved</param>
</entry>
<entry value="2501" name="MAV_CMD_VIDEO_STOP_CAPTURE">
<description>WIP: Stop the current video capture (recording). Use NAN for reserved values.</description>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)</param>
<param index="1">Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)</param>
<param index="2">Reserved</param>
</entry>
<entry value="2502" name="MAV_CMD_VIDEO_START_STREAMING">
Expand Down Expand Up @@ -2589,6 +2603,24 @@
<description>Landing target represented by a pre-defined visual shape/feature (ex: X-marker, H-marker, square)</description>
</entry>
</enum>
<enum name="CAMERA_CAP_FLAGS">
<description>Camera capability flags (Bitmap).</description>
<entry value="1" name="CAMERA_CAP_FLAGS_CAPTURE_VIDEO">
<description>Camera is able to record video.</description>
</entry>
<entry value="2" name="CAMERA_CAP_FLAGS_CAPTURE_IMAGE">
<description>Camera is able to capture images.</description>
</entry>
<entry value="4" name="CAMERA_CAP_FLAGS_HAS_MODES">
<description>Camera has separate Video and Image/Photo modes (MAV_CMD_SET_CAMERA_MODE)</description>
</entry>
<entry value="8" name="CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE">
<description>Camera can capture images while in video mode</description>
</entry>
<entry value="16" name="CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE">
<description>Camera can capture videos while in Photo/Image mode</description>
</entry>
</enum>
<enum name="PARAM_ACK">
<description>Result from a PARAM_EXT_SET message.</description>
<entry value="0" name="PARAM_ACK_ACCEPTED">
Expand Down Expand Up @@ -4092,37 +4124,40 @@
<message id="259" name="CAMERA_INFORMATION">
<description>WIP: Information about a camera</description>
<field type="uint32_t" name="time_boot_ms" units="ms">Timestamp (milliseconds since system boot)</field>
<field type="uint8_t" name="camera_id">Camera ID (1 for first, 2 for second, etc.)</field>
<field type="uint8_t" name="camera_count">Number of cameras</field>
<field type="uint8_t" name="camera_id">Camera ID (1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)</field>
<field type="uint8_t" name="camera_count">Number of cameras (EXPERIMENTAL: IT WILL BE REMOVED)</field>
<field type="uint8_t[32]" name="vendor_name">Name of the camera vendor</field>
<field type="uint8_t[32]" name="model_name">Name of the camera model</field>
<field type="uint32_t" name="firmware_version">Version of the camera firmware</field>
<field type="uint32_t" name="firmware_version">Version of the camera firmware (v &lt;&lt; 24 &amp; 0xff = Dev, v &lt;&lt; 16 &amp; 0xff = Patch, v &lt;&lt; 8 &amp; 0xff = Minor, v &amp; 0xff = Major)</field>
<field type="float" name="focal_length" units="mm">Focal length in mm</field>
<field type="float" name="sensor_size_h" units="mm">Image sensor size horizontal in mm</field>
<field type="float" name="sensor_size_v" units="mm">Image sensor size vertical in mm</field>
<field type="uint16_t" name="resolution_h" units="pix">Image resolution in pixels horizontal</field>
<field type="uint16_t" name="resolution_v" units="pix">Image resolution in pixels vertical</field>
<field type="uint8_t" name="lens_id">Reserved for a lens ID</field>
<field type="uint32_t" name="flags" enum="CAMERA_CAP_FLAGS">CAMERA_CAP_FLAGS enum flags (bitmap) describing camera capabilities.</field>
<field type="uint16_t" name="cam_definition_version">Camera definition version (iteration)</field>
<field type="uint8_t[140]" name="cam_definition_uri">Camera definition URI (if any, otherwise only basic functions will be available).</field>
</message>
<message id="260" name="CAMERA_SETTINGS">
<description>WIP: Settings of a camera, can be requested using MAV_CMD_REQUEST_CAMERA_SETTINGS and written using MAV_CMD_SET_CAMERA_SETTINGS</description>
<description>WIP: Settings of a camera, can be requested using MAV_CMD_REQUEST_CAMERA_SETTINGS and written using MAV_CMD_SET_CAMERA_SETTINGS.</description>
<field type="uint32_t" name="time_boot_ms" units="ms">Timestamp (milliseconds since system boot)</field>
<field type="uint8_t" name="camera_id">Camera ID (1 for first, 2 for second, etc.)</field>
<field type="uint8_t" name="exposure_mode">0: full auto 1: full manual 2: aperture priority 3: shutter priority</field>
<field type="float" name="aperture">Aperture is 1/value</field>
<field type="float" name="shutter_speed" units="s">Shutter speed in seconds</field>
<field type="float" name="iso_sensitivity">ISO sensitivity</field>
<field type="float" name="ev">Exposure Value</field>
<field type="float" name="white_balance" units="K">Color temperature in degrees Kelvin. (0: Auto WB, -1: Locked at auto value)</field>
<field type="uint8_t" name="mode_id">Reserved for a camera mode ID. (0: Photo 1: Video)</field>
<field type="uint8_t" name="audio_recording">Audio recording enabled (0: off 1: on)</field>
<field type="uint8_t" name="color_mode_id">Reserved for a color mode ID (Neutral, Vivid, etc.)</field>
<field type="uint8_t" name="image_format_id">Reserved for image format ID (Jpeg/Raw/Jpeg+Raw)</field>
<field type="uint8_t" name="image_quality_id">Reserved for image quality ID (Compression)</field>
<field type="uint8_t" name="metering_mode_id">Reserved for metering mode ID (Average, Center, Spot, etc.)</field>
<field type="uint8_t" name="flicker_mode_id">Reserved for flicker mode ID (Auto, 60Hz, 50Hz, etc.)</field>
<field type="uint8_t" name="photo_resolution_id">Photo resolution ID (4000x3000, 2560x1920, etc.)</field>
<field type="uint8_t" name="video_resolution_and_rate_id">Video resolution and rate ID (4K 60 Hz, 4K 30 Hz, HD 60 Hz, HD 30 Hz, etc.)</field>
<field type="uint8_t" name="camera_id">Camera ID (1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)</field>
<field type="uint8_t" name="exposure_mode">0: full auto 1: full manual 2: aperture priority 3: shutter priority. (EXPERIMENTAL: IT WILL BE REMOVED)</field>
<field type="float" name="aperture">Aperture is 1/value. (EXPERIMENTAL: IT WILL BE REMOVED)</field>
<field type="float" name="shutter_speed" units="s">Shutter speed in seconds. (EXPERIMENTAL: IT WILL BE REMOVED)</field>
<field type="float" name="iso_sensitivity">ISO sensitivity. (EXPERIMENTAL: IT WILL BE REMOVED)</field>
<field type="float" name="ev">Exposure Value. (EXPERIMENTAL: IT WILL BE REMOVED)</field>
<field type="float" name="white_balance" units="K">Color temperature in degrees Kelvin. (0: Auto WB, -1: Locked at auto value). (EXPERIMENTAL: IT WILL BE REMOVED)</field>
<field type="uint8_t" name="mode_id">Camera mode ID (0: Photo 1: Video)</field>
<field type="uint8_t" name="audio_recording">Audio recording enabled (0: off 1: on). (EXPERIMENTAL: IT WILL BE REMOVED)</field>
<field type="uint8_t" name="color_mode_id">Reserved for a color mode ID (Neutral, Vivid, etc.). (EXPERIMENTAL: IT WILL BE REMOVED)</field>
<field type="uint8_t" name="image_format_id">Reserved for image format ID (Jpeg/Raw/Jpeg+Raw). (EXPERIMENTAL: IT WILL BE REMOVED)</field>
<field type="uint8_t" name="image_quality_id">Reserved for image quality ID (Compression). (EXPERIMENTAL: IT WILL BE REMOVED)</field>
<field type="uint8_t" name="metering_mode_id">Reserved for metering mode ID (Average, Center, Spot, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)</field>
<field type="uint8_t" name="flicker_mode_id">Reserved for flicker mode ID (Auto, 60Hz, 50Hz, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)</field>
<field type="uint8_t" name="photo_resolution_id">Photo resolution ID (4000x3000, 2560x1920, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)</field>
<field type="uint8_t" name="video_resolution_and_rate_id">Video resolution and rate ID (4K 60 Hz, 4K 30 Hz, HD 60 Hz, HD 30 Hz, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)</field>
</message>
<message id="261" name="STORAGE_INFORMATION">
<description>WIP: Information about a storage medium.</description>
Expand Down Expand Up @@ -4150,7 +4185,7 @@
<description>WIP: Information about a captured image</description>
<field type="uint32_t" name="time_boot_ms" units="ms">Timestamp (milliseconds since system boot)</field>
<field type="uint64_t" name="time_utc" units="us">Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown.</field>
<field type="uint8_t" name="camera_id">Camera ID (1 for first, 2 for second, etc.)</field>
<field type="uint8_t" name="camera_id">Camera ID (1 for first, 2 for second, etc.) (EXPERIMENTAL: IT WILL BE REMOVED)</field>
<field type="int32_t" name="lat" units="degE7">Latitude, expressed as degrees * 1E7 where image was taken</field>
<field type="int32_t" name="lon" units="degE7">Longitude, expressed as degrees * 1E7 where capture was taken</field>
<field type="int32_t" name="alt" units="m">Altitude in meters, expressed as * 1E3 (AMSL, not WGS84) where image was taken</field>
Expand Down

0 comments on commit e722542

Please sign in to comment.