mirror of
https://github.com/mavlink/mavlink.git
synced 2026-06-19 07:35:34 +00:00
common.xml: reorder CANFD_FRAME and CAN_FILTER_MODIFY to be next to CAN_FRAME (numerically sequential) (#2483)
This commit is contained in:
@@ -7975,6 +7975,24 @@
|
||||
<field type="uint32_t" name="id">Frame ID</field>
|
||||
<field type="uint8_t[8]" name="data">Frame data</field>
|
||||
</message>
|
||||
<message id="387" name="CANFD_FRAME">
|
||||
<description>A forwarded CANFD frame as requested by MAV_CMD_CAN_FORWARD. These are separated from CAN_FRAME as they need different handling (eg. TAO handling)</description>
|
||||
<field type="uint8_t" name="target_system">System ID.</field>
|
||||
<field type="uint8_t" name="target_component">Component ID.</field>
|
||||
<field type="uint8_t" name="bus">bus number</field>
|
||||
<field type="uint8_t" name="len">Frame length</field>
|
||||
<field type="uint32_t" name="id">Frame ID</field>
|
||||
<field type="uint8_t[64]" name="data">Frame data</field>
|
||||
</message>
|
||||
<message id="388" name="CAN_FILTER_MODIFY">
|
||||
<description>Modify the filter of what CAN messages to forward over the mavlink. This can be used to make CAN forwarding work well on low bandwidth links. The filtering is applied on bits 8 to 24 of the CAN id (2nd and 3rd bytes) which corresponds to the DroneCAN message ID for DroneCAN. Filters with more than 16 IDs can be constructed by sending multiple CAN_FILTER_MODIFY messages.</description>
|
||||
<field type="uint8_t" name="target_system">System ID.</field>
|
||||
<field type="uint8_t" name="target_component">Component ID.</field>
|
||||
<field type="uint8_t" name="bus">bus number</field>
|
||||
<field type="uint8_t" name="operation" enum="CAN_FILTER_OP">what operation to perform on the filter list. See CAN_FILTER_OP enum.</field>
|
||||
<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>
|
||||
@@ -8143,24 +8161,6 @@
|
||||
<field type="float" name="max_strobe_period" units="s">Maximum strobing period in seconds</field>
|
||||
</message>
|
||||
<!-- The message ids 510 and 511 are reserved for ABSOLUTE_TARGET and RELATIVE_TARGET, currently in development.xml. -->
|
||||
<message id="387" name="CANFD_FRAME">
|
||||
<description>A forwarded CANFD frame as requested by MAV_CMD_CAN_FORWARD. These are separated from CAN_FRAME as they need different handling (eg. TAO handling)</description>
|
||||
<field type="uint8_t" name="target_system">System ID.</field>
|
||||
<field type="uint8_t" name="target_component">Component ID.</field>
|
||||
<field type="uint8_t" name="bus">bus number</field>
|
||||
<field type="uint8_t" name="len">Frame length</field>
|
||||
<field type="uint32_t" name="id">Frame ID</field>
|
||||
<field type="uint8_t[64]" name="data">Frame data</field>
|
||||
</message>
|
||||
<message id="388" name="CAN_FILTER_MODIFY">
|
||||
<description>Modify the filter of what CAN messages to forward over the mavlink. This can be used to make CAN forwarding work well on low bandwidth links. The filtering is applied on bits 8 to 24 of the CAN id (2nd and 3rd bytes) which corresponds to the DroneCAN message ID for DroneCAN. Filters with more than 16 IDs can be constructed by sending multiple CAN_FILTER_MODIFY messages.</description>
|
||||
<field type="uint8_t" name="target_system">System ID.</field>
|
||||
<field type="uint8_t" name="target_component">Component ID.</field>
|
||||
<field type="uint8_t" name="bus">bus number</field>
|
||||
<field type="uint8_t" name="operation" enum="CAN_FILTER_OP">what operation to perform on the filter list. See CAN_FILTER_OP enum.</field>
|
||||
<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>
|
||||
<!-- Rover specific messages -->
|
||||
<message id="9000" name="WHEEL_DISTANCE">
|
||||
<description>Cumulative distance traveled for each reported wheel.</description>
|
||||
|
||||
Reference in New Issue
Block a user