@@ -521,6 +521,31 @@ bool canard_1v0_subscribe_response(canard_t* const sel
521521
522522// --------------------------------- UAVCAN v0 & DroneCAN legacy compatibility API ---------------------------------
523523
524+ /// ATTENTION: Due to the v0 design, the problem of protocol version detection for correct frame parsing given
525+ /// multi-frame transfers is undecidable without imposing constraints on the network configuration.
526+ ///
527+ /// The core problem is that the protocol version is encoded in the initial state of the toggle bit, which is
528+ /// by definition only observable in the first frame of a transfer; if there happen to be concurrent multi-frame
529+ /// transfers emitted by the same node under the same transfer-ID under different versions, and their port-IDs
530+ /// (and in the case of service transfers also the destination node-IDs, with a 1-bit bias) happen to alias
531+ /// pathologically, remote subscribers will observe the two frame sequences as belonging to the same transfer.
532+ ///
533+ /// Various heuristics exist, but due to intricate edge cases no robust solution exists for the general case.
534+ /// The recommended solution is to adopt at least one of the following constraints on the network configuration:
535+ ///
536+ /// - A single node-ID can only emit transfers of any single protocol version. The disambiguation problem is addressed
537+ /// by the fact that the multi-frame reassembly state machine necessarily indexes states by the remote node-ID
538+ /// (this is not an implementation detail but a requirement from the Specification of both UAVCAN v0 and Cyphal/CAN).
539+ /// The first frame of any transfer is only accepted if the protocol version matches (it is observable reliably
540+ /// in this case); subsequent frames even if aliased will not cause data corruption because without the start frame
541+ /// the transfer will not be accepted. An application may maintain more than one node-ID with multiple canard_t.
542+ ///
543+ /// - A single node-ID may emit transfers of both versions simultaneously as long as the resulting CAN IDs do not alias.
544+ /// For example, if a v0 data type ID is chosen such that it maps a 1-bit onto a reserved 0-bit of the v1 CAN ID,
545+ /// no ambiguity will occur.
546+ ///
547+ /// The above concerns only data emission. It is always safe to receive transfers of any version from any node.
548+
524549/// The legacy UAVCAN v0 protocol has 5-bit priority, which is obtained from 3-bit priority by left-shifting.
525550/// All legacy transfers are always sent in Classic CAN mode regardless of the FD flag.
526551bool canard_0v1_publish (canard_t * const self ,
0 commit comments