mirror of https://github.com/ArduPilot/ardupilot
AP_Bootloader: 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 but the code now correctly ignores that ID and retries the allocation as it did before.
This commit is contained in:
parent
41753b43d7
commit
4df758f52a
|
@ -429,7 +429,7 @@ static void handle_allocation_response(CanardInstance* ins, CanardRxTransfer* tr
|
||||||
// The allocator has confirmed part of unique ID, switching to the next stage and updating the timeout.
|
// The allocator has confirmed part of unique ID, switching to the next stage and updating the timeout.
|
||||||
node_id_allocation_unique_id_offset = msg.unique_id.len;
|
node_id_allocation_unique_id_offset = msg.unique_id.len;
|
||||||
send_next_node_id_allocation_request_at_ms -= UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS;
|
send_next_node_id_allocation_request_at_ms -= UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS;
|
||||||
} 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
|
// Allocation complete - copying the allocated node ID from the message
|
||||||
canardSetLocalNodeID(ins, msg.node_id);
|
canardSetLocalNodeID(ins, msg.node_id);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue