From 6dac9679ded48f96a44aab4c56958755b1d8638a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 14 May 2026 16:42:31 +1000 Subject: [PATCH] common.xml: reorder CANFD_FRAME and CAN_FILTER_MODIFY to be next to CAN_FRAME (numerically sequential) (#2483) --- message_definitions/v1.0/common.xml | 36 ++++++++++++++--------------- 1 file changed, 18 insertions(+), 18 deletions(-) diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml index 8af08165..1b8cad2b 100644 --- a/message_definitions/v1.0/common.xml +++ b/message_definitions/v1.0/common.xml @@ -7975,6 +7975,24 @@ Frame ID Frame data + + 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) + System ID. + Component ID. + bus number + Frame length + Frame ID + Frame data + + + 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. + System ID. + Component ID. + bus number + what operation to perform on the filter list. See CAN_FILTER_OP enum. + number of IDs in filter list + filter IDs, length num_ids + Hardware status sent by an onboard computer. 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. @@ -8143,24 +8161,6 @@ Maximum strobing period in seconds - - 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) - System ID. - Component ID. - bus number - Frame length - Frame ID - Frame data - - - 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. - System ID. - Component ID. - bus number - what operation to perform on the filter list. See CAN_FILTER_OP enum. - number of IDs in filter list - filter IDs, length num_ids - Cumulative distance traveled for each reported wheel.