Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

common: add set-camera-source command #351

Merged
merged 2 commits into from
Mar 18, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
45 changes: 45 additions & 0 deletions message_definitions/v1.0/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -732,6 +732,21 @@
<description>Storage type is other, not listed type.</description>
</entry>
</enum>
<enum name="STORAGE_USAGE_FLAG">
<description>Flags to indicate usage for a particular storage (see STORAGE_INFORMATION.storage_usage and MAV_CMD_SET_STORAGE_USAGE).</description>
<entry value="1" name="STORAGE_USAGE_FLAG_SET">
<description>Always set to 1 (indicates STORAGE_INFORMATION.storage_usage is supported).</description>
</entry>
<entry value="2" name="STORAGE_USAGE_FLAG_PHOTO">
<description>Storage for saving photos.</description>
</entry>
<entry value="4" name="STORAGE_USAGE_FLAG_VIDEO">
<description>Storage for saving videos.</description>
</entry>
<entry value="8" name="STORAGE_USAGE_FLAG_LOGS">
<description>Storage for saving logs.</description>
</entry>
</enum>
<enum name="AUTOTUNE_AXIS" bitmask="true">
<description>Enable axes that will be tuned via autotuning. Used in MAV_CMD_DO_AUTOTUNE_ENABLE.</description>
<entry value="0" name="AUTOTUNE_AXIS_DEFAULT">
Expand Down Expand Up @@ -1657,6 +1672,21 @@
<param index="4" reserved="true" default="NaN"/>
<param index="7" reserved="true" default="NaN"/>
</entry>
<entry value="533" name="MAV_CMD_SET_STORAGE_USAGE" hasLocation="false" isDestination="false">
<description>Set that a particular storage is the preferred location for saving photos, videos, and/or other media (e.g. to set that an SD card is used for storing videos).
There can only be one preferred save location for each particular media type: setting a media usage flag will clear/reset that same flag if set on any other storage.
If no flag is set the system should use its default storage.
A target system can choose to always use default storage, in which case it should ACK the command with MAV_RESULT_UNSUPPORTED.
A target system can choose to not allow a particular storage to be set as preferred storage, in which case it should ACK the command with MAV_RESULT_DENIED.</description>
<param index="1" label="Storage ID" minValue="0" increment="1">Storage ID (1 for first, 2 for second, etc.)</param>
<param index="2" label="Usage" enum="STORAGE_USAGE_FLAG">Usage flags</param>
</entry>
<entry value="534" name="MAV_CMD_SET_CAMERA_SOURCE" hasLocation="false" isDestination="false">
<description>Set camera source. Changes the camera's active sources on cameras with multiple image sensors.</description>
<param index="1" label="device id">Component Id of camera to address or 1-6 for non-MAVLink cameras, 0 for all cameras.</param>
<param index="2" label="primary source" enum="CAMERA_SOURCE">Primary Source</param>
<param index="3" label="secondary source" enum="CAMERA_SOURCE">Secondary Source. If non-zero the second source will be displayed as picture-in-picture.</param>
</entry>
<entry value="600" name="MAV_CMD_JUMP_TAG" hasLocation="false" isDestination="false">
<description>Tagged jump target. Can be jumped to with MAV_CMD_DO_JUMP_TAG.</description>
<param index="1" label="Tag" minValue="0" increment="1">Tag.</param>
Expand Down Expand Up @@ -3357,6 +3387,21 @@
<description>Continuous auto focus. Mainly used for dynamic scenes. Abbreviated as AF-C.</description>
</entry>
</enum>
<enum name="CAMERA_SOURCE">
<description>Camera sources for MAV_CMD_SET_CAMERA_SOURCE</description>
<entry value="0" name="CAMERA_SOURCE_DEFAULT">
<description>Default camera source.</description>
</entry>
<entry value="1" name="CAMERA_SOURCE_RGB">
<description>RGB camera source.</description>
</entry>
<entry value="2" name="CAMERA_SOURCE_IR">
<description>IR camera source.</description>
</entry>
<entry value="3" name="CAMERA_SOURCE_NDVI">
<description>NDVI camera source.</description>
</entry>
</enum>
<enum name="PARAM_ACK">
<description>Result from PARAM_EXT_SET message (or a PARAM_SET within a transaction).</description>
<entry value="0" name="PARAM_ACK_ACCEPTED">
Expand Down
Loading