Skip to content
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
40 changes: 40 additions & 0 deletions message_definitions/v1.0/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4994,6 +4994,21 @@
<description>Simulation is using lockstep</description>
</entry>
</enum>
<enum name="COMPUTER_STATUS_FLAGS" bitmask="true">
Comment thread
marifante marked this conversation as resolved.
<description>Flags used to report computer status.</description>
<entry value="1" name="COMPUTER_STATUS_FLAGS_UNDER_VOLTAGE">
<description>Indicates if the system is experiencing voltage outside of acceptable range.</description>
</entry>
<entry value="2" name="COMPUTER_STATUS_FLAGS_CPU_THROTTLE">
<description>Indicates if CPU throttling is active.</description>
</entry>
<entry value="4" name="COMPUTER_STATUS_FLAGS_THERMAL_THROTTLE">
<description>Indicates if thermal throttling is active.</description>
</entry>
<entry value="8" name="COMPUTER_STATUS_FLAGS_DISK_FULL">
<description>Indicates if main disk is full.</description>
</entry>
</enum>
<enum name="AIRSPEED_SENSOR_FLAGS" bitmask="true">
<description>Airspeed sensor flags</description>
<entry value="1" name="AIRSPEED_SENSOR_UNHEALTHY">
Expand Down Expand Up @@ -7355,6 +7370,31 @@
<field type="uint8_t" name="num_ids">number of IDs in filter list</field>
<field type="uint16_t[16]" name="ids">filter IDs, length num_ids</field>
</message>
<message id="390" name="ONBOARD_COMPUTER_STATUS">
<description>Hardware status sent by an onboard computer.</description>
<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>
<field type="uint32_t" name="uptime" units="ms">Time since system boot.</field>
<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>
<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>
<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>
<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>
<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>
<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>
<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>
<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>
<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>
<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>
<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>
<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>
<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>
<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>
<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>
<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>
<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>
<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>
<extensions/>
<field type="uint16_t" name="status_flags" enum="COMPUTER_STATUS_FLAGS">Bitmap of status flags.</field>
</message>
<!-- Rover specific messages -->
<message id="9000" name="WHEEL_DISTANCE">
<description>Cumulative distance traveled for each reported wheel.</description>
Expand Down
Loading