Skip to content

Commit a7b7a4a

Browse files
committed
common: sync ONBOARD_COMPUTER_STATUS (id=390) from upstream mavlink/mavlink
ONBOARD_COMPUTER_STATUS was added to mavlink/mavlink in August 2019 (PR mavlink#1186) and has been part of the standard common.xml ever since. This commit syncs it into ArduPilot/mavlink so that ArduPilot builds its CRC_EXTRA map with knowledge of message ID 390, enabling it to validate and route frames sent by companion computers instead of silently dropping them. Also adds the COMPUTER_STATUS_FLAGS bitmask enum referenced by the status_flags extension field.
1 parent 37d35a6 commit a7b7a4a

File tree

1 file changed

+42
-0
lines changed

1 file changed

+42
-0
lines changed

message_definitions/v1.0/common.xml

Lines changed: 42 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4993,6 +4993,22 @@
49934993
<description>True if the data from this sensor is being actively used by the flight controller for guidance, navigation or control.</description>
49944994
</entry>
49954995
</enum>
4996+
4997+
<enum name="COMPUTER_STATUS_FLAGS" bitmask="true">
4998+
<description>Flags used to report computer status.</description>
4999+
<entry value="1" name="COMPUTER_STATUS_FLAGS_UNDER_VOLTAGE">
5000+
<description>Indicates if the system is experiencing voltage outside of acceptable range.</description>
5001+
</entry>
5002+
<entry value="2" name="COMPUTER_STATUS_FLAGS_CPU_THROTTLE">
5003+
<description>Indicates if CPU throttling is active.</description>
5004+
</entry>
5005+
<entry value="4" name="COMPUTER_STATUS_FLAGS_THERMAL_THROTTLE">
5006+
<description>Indicates if thermal throttling is active.</description>
5007+
</entry>
5008+
<entry value="8" name="COMPUTER_STATUS_FLAGS_DISK_FULL">
5009+
<description>Indicates if main disk is full.</description>
5010+
</entry>
5011+
</enum>
49965012
</enums>
49975013
<messages>
49985014
<message id="1" name="SYS_STATUS">
@@ -7345,6 +7361,32 @@
73457361
<field type="uint8_t" name="num_ids">number of IDs in filter list</field>
73467362
<field type="uint16_t[16]" name="ids">filter IDs, length num_ids</field>
73477363
</message>
7364+
<message id="390" name="ONBOARD_COMPUTER_STATUS">
7365+
<description>Hardware status sent by an onboard computer.</description>
7366+
<field type="uint64_t" name="time_usec" units="us">Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.</field>
7367+
<field type="uint32_t" name="uptime" units="ms">Time since system boot.</field>
7368+
<field type="uint8_t" name="type">Type of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers.</field>
7369+
<field type="uint8_t[8]" name="cpu_cores" invalid="[UINT8_MAX]">CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused.</field>
7370+
<field type="uint8_t[10]" name="cpu_combined" invalid="[UINT8_MAX]">Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused.</field>
7371+
<field type="uint8_t[4]" name="gpu_cores" invalid="[UINT8_MAX]">GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused.</field>
7372+
<field type="uint8_t[10]" name="gpu_combined" invalid="[UINT8_MAX]">Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused.</field>
7373+
<field type="int8_t" name="temperature_board" units="degC" invalid="INT8_MAX">Temperature of the board. A value of INT8_MAX implies the field is unused.</field>
7374+
<field type="int8_t[8]" name="temperature_core" units="degC" invalid="[INT8_MAX]">Temperature of the CPU core. A value of INT8_MAX implies the field is unused.</field>
7375+
<field type="int16_t[4]" name="fan_speed" units="rpm" invalid="[INT16_MAX]">Fan speeds. A value of INT16_MAX implies the field is unused.</field>
7376+
<field type="uint32_t" name="ram_usage" units="MiB" invalid="UINT32_MAX">Amount of used RAM on the component system. A value of UINT32_MAX implies the field is unused.</field>
7377+
<field type="uint32_t" name="ram_total" units="MiB" invalid="UINT32_MAX">Total amount of RAM on the component system. A value of UINT32_MAX implies the field is unused.</field>
7378+
<field type="uint32_t[4]" name="storage_type" invalid="[UINT32_MAX]">Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused.</field>
7379+
<field type="uint32_t[4]" name="storage_usage" units="MiB" invalid="[UINT32_MAX]">Amount of used storage space on the component system. A value of UINT32_MAX implies the field is unused.</field>
7380+
<field type="uint32_t[4]" name="storage_total" units="MiB" invalid="[UINT32_MAX]">Total amount of storage space on the component system. A value of UINT32_MAX implies the field is unused.</field>
7381+
<field type="uint32_t[6]" name="link_type">Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary</field>
7382+
<field type="uint32_t[6]" name="link_tx_rate" units="KiB/s" invalid="[UINT32_MAX]">Network traffic from the component system. A value of UINT32_MAX implies the field is unused.</field>
7383+
<field type="uint32_t[6]" name="link_rx_rate" units="KiB/s" invalid="[UINT32_MAX]">Network traffic to the component system. A value of UINT32_MAX implies the field is unused.</field>
7384+
<field type="uint32_t[6]" name="link_tx_max" units="KiB/s" invalid="[UINT32_MAX]">Network capacity from the component system. A value of UINT32_MAX implies the field is unused.</field>
7385+
<field type="uint32_t[6]" name="link_rx_max" units="KiB/s" invalid="[UINT32_MAX]">Network capacity to the component system. A value of UINT32_MAX implies the field is unused.</field>
7386+
<extensions/>
7387+
<field type="uint16_t" name="status_flags" enum="COMPUTER_STATUS_FLAGS">Bitmap of status flags.</field>
7388+
</message>
7389+
73487390
<!-- Rover specific messages -->
73497391
<message id="9000" name="WHEEL_DISTANCE">
73507392
<description>Cumulative distance traveled for each reported wheel.</description>

0 commit comments

Comments
 (0)