Skip to content

Commit

Permalink
Clarifying what to do with reserved values
Browse files Browse the repository at this point in the history
Clarify that a STORAGE_INFORMATION message is sent once formatting storage is completed.
  • Loading branch information
dogmaphobic authored and LorenzMeier committed Jun 29, 2017
1 parent 35a89a2 commit a3b7409
Showing 1 changed file with 10 additions and 10 deletions.
20 changes: 10 additions & 10 deletions message_definitions/v1.0/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -1375,7 +1375,7 @@
<param index="2">Reserved (all remaining params)</param>
</entry>
<entry value="521" name="MAV_CMD_REQUEST_CAMERA_INFORMATION">
<description>WIP: Request camera information (CAMERA_INFORMATION)</description>
<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="2">0: No action 1: Request camera capabilities</param>
<param index="3">Reserved (all remaining params)</param>
Expand All @@ -1387,7 +1387,7 @@
<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 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.</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 +1397,7 @@
<param index="7">White balance (color temperature in K) (0: Auto WB)</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 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.</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 @@ -1413,7 +1413,7 @@
<param index="3">Reserved (all remaining params)</param>
</entry>
<entry value="526" name="MAV_CMD_STORAGE_FORMAT">
<description>WIP: Format a storage medium</description>
<description>WIP: Format a storage medium. Once format is complete, a STORAGE_INFORMATION message is sent.</description>
<param index="1">Storage ID (1 for first, 2 for second, etc.)</param>
<param index="2">0: No action 1: Format storage</param>
<param index="3">Reserved (all remaining params)</param>
Expand All @@ -1436,21 +1436,21 @@
<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 values you don't want to change.</description>
<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>
</entry>
<entry value="531" name="MAV_CMD_SET_CAMERA_SETTINGS_3">
<description>WIP: Set the camera settings part 3 (CAMERA_SETTINGS). Use NAN for 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.</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.</description>
<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="2">Duration between two consecutive pictures (in seconds)</param>
<param index="3">Number of images to capture total - 0 for unlimited capture</param>
Expand All @@ -1462,7 +1462,7 @@
<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</description>
<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="2">Sequence number for missing CAMERA_IMAGE_CAPTURE packet</param>
<param index="3">Reserved (all remaining params)</param>
Expand All @@ -1474,13 +1474,13 @@
<param index="3">1 to pause triggering, but without switching the camera off or retracting it. -1 to ignore</param>
</entry>
<entry value="2500" name="MAV_CMD_VIDEO_START_CAPTURE">
<description>WIP: Starts video capture (recording)</description>
<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="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)</description>
<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="2">Reserved</param>
</entry>
Expand Down

0 comments on commit a3b7409

Please sign in to comment.