Skip to content

Commit

Permalink
common: updates to camera-thermal-range from peer review
Browse files Browse the repository at this point in the history
  • Loading branch information
hamishwillee authored and tridge committed Sep 9, 2024
1 parent 344dfee commit cdfe7a8
Showing 1 changed file with 7 additions and 5 deletions.
12 changes: 7 additions & 5 deletions message_definitions/v1.0/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3311,7 +3311,7 @@
<description>Camera supports tracking geo status (CAMERA_TRACKING_GEO_STATUS).</description>
</entry>
<entry value="4096" name="CAMERA_CAP_FLAGS_HAS_THERMAL_RANGE">
<description>Camera supports absolute thermal range (request CAMERA_THERMAL_RANGE with MAV_CMD_REQUEST_MESSAGE).</description>
<description>Camera supports absolute thermal range (request CAMERA_THERMAL_RANGE with MAV_CMD_REQUEST_MESSAGE) (WIP).</description>
</entry>
</enum>
<enum name="VIDEO_STREAM_STATUS_FLAGS" bitmask="true">
Expand All @@ -3323,7 +3323,7 @@
<description>Stream is thermal imaging</description>
</entry>
<entry value="4" name="VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED">
<description>Stream can report absolute thermal range (see CAMERA_THERMAL_RANGE)</description>
<description>Stream can report absolute thermal range (see CAMERA_THERMAL_RANGE). (WIP).</description>
</entry>
</enum>
<enum name="VIDEO_STREAM_TYPE">
Expand Down Expand Up @@ -6112,10 +6112,12 @@
<field type="float" name="hdg_acc" units="rad" invalid="NaN">Accuracy of heading, in NED. NAN if unknown</field>
</message>
<message id="277" name="CAMERA_THERMAL_RANGE">
<description>Camera absolute thermal range. This can be streamed when the associated `VIDEO_STREAM_STATUS.flag` bit `VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED` is set, but a GCS may choose to only request it for the current active stream. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval (param3 indicates the stream id of the current camera, or 0 for all streams, param4 indicates the target camera_device_id for autopilot-attached cameras or 0 for MAVLink cameras).</description>
<wip/>
<!-- This message is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
<description>Camera absolute thermal range. This can be streamed when the associated `VIDEO_STREAM_STATUS.flag` bit `VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED` is set, but a GCS may choose to only request it for the current active stream. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval (param3 indicates the stream id of the current camera, or 0 for all streams, param4 indicates the target camera_device_id for autopilot-attached cameras or 0 for MAVLink cameras).</description>
<field type="uint32_t" name="time_boot_ms" units="ms">Timestamp (time since system boot).</field>
<field type="uint8_t" name="stream_id" invalid="0" instance="true">Video Stream ID (1 for first, 2 for second, etc.)</field>
<field type="uint8_t" name="camera_device_id" invalid="0">Camera id of a camera associated with this component. This is the component id of a proxied MAVLink camera, or 1-6 for a non-MAVLink camera attached to the component. Use 0 if the component is a camera (not something else providing access to a camera).</field>
<field type="uint8_t" name="stream_id" minValue="1" instance="true">Video Stream ID (1 for first, 2 for second, etc.)</field>
<field type="uint8_t" name="camera_device_id" default="0" minValue="0" maxValue="6">Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id).</field>
<field type="float" name="max" units="degC">Temperature max.</field>
<field type="float" name="max_point_x" invalid="NaN">Temperature max point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown.</field>
<field type="float" name="max_point_y" invalid="NaN">Temperature max point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown.</field>
Expand Down

0 comments on commit cdfe7a8

Please sign in to comment.