mirror of https://github.com/ArduPilot/ardupilot
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.
This commit is contained in:
parent
854b769cfe
commit
ebcb753acc
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue