Skip to content

Commit

Permalink
common: add camera-thermal-status
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Aug 24, 2024
1 parent 93e65a4 commit 3c6affe
Showing 1 changed file with 21 additions and 0 deletions.
21 changes: 21 additions & 0 deletions message_definitions/v1.0/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3386,6 +3386,15 @@
<description>Target data within status message (Point or Rectangle)</description>
</entry>
</enum>
<enum name="CAMERA_THERMAL_STATUS_FLAGS">
<description>Camera thermal status flags</description>
<entry value="0" name="CAMERA_THERMAL_UNAVAILABLE">
<description>Temperatures unavailable</description>
</entry>
<entry value="1" name="CAMERA_THERMAL_AVAILABLE">
<description>Temperatures available</description>
</entry>
</enum>
<enum name="CAMERA_ZOOM_TYPE">
<description>Zoom types for MAV_CMD_SET_CAMERA_ZOOM</description>
<entry value="0" name="ZOOM_TYPE_STEP">
Expand Down Expand Up @@ -6105,6 +6114,18 @@
<field type="float" name="hdg" units="rad" invalid="NaN">Heading in radians, in NED. NAN if unknown</field>
<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_STATUS">
<description>Camera thermal status, sent while thermal camera is capturing absolute temperatures. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval.</description>
<field type="uint32_t" name="time_boot_ms" units="ms">Timestamp (time since system boot).</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="status" enum="CAMERA_THERMAL_STATUS_FLAGS">Thermal status.</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>
<field type="float" name="min" units="degC">Temperature min.</field>
<field type="float" name="min_point_x" invalid="NaN">Temperature min point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown.</field>
<field type="float" name="min_point_y" invalid="NaN">Temperature min point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown.</field>
</message>
<message id="280" name="GIMBAL_MANAGER_INFORMATION">
<description>Information about a high level gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE.</description>
<field type="uint32_t" name="time_boot_ms" units="ms">Timestamp (time since system boot).</field>
Expand Down

0 comments on commit 3c6affe

Please sign in to comment.