From ebcb753acc7c1c2decf35ab3fd074b7d5e9056a0 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Sun, 8 Sep 2024 13:03:50 -0500 Subject: [PATCH] AP_Periph: reject allocation of broadcast node ID It is technically legal to receive an "allocation" of the broadcast node ID. Fortunately, this was already ignored by `canardSetLocalNodeID`, though it would trigger an assertion failure if those were enabled. Fix by rejecting that ID. There is effectively no change in behavior (except possibly fixes using moving baseline GPSes) but the code now correctly ignores that ID and retries the allocation as it did before. --- Tools/AP_Periph/can.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index 036cbed6df..8b42fb1963 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -472,7 +472,7 @@ void AP_Periph_FW::handle_allocation_response(CanardInstance* canard_instance, C dronecan.send_next_node_id_allocation_request_at_ms -= UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS; printf("Matching allocation response: %d\n", msg.unique_id.len); - } else { + } else if (msg.node_id != CANARD_BROADCAST_NODE_ID) { // new ID valid? (if not we will time out and start over) // Allocation complete - copying the allocated node ID from the message canardSetLocalNodeID(canard_instance, msg.node_id); printf("IF%d Node ID allocated: %d\n", dronecan.dna_interface, msg.node_id);