Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Bootloader: reject allocation of broadcast node ID #28327

Merged
merged 1 commit into from
Oct 8, 2024

Conversation

tpwrules
Copy link
Contributor

@tpwrules tpwrules commented Oct 7, 2024

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.

Similar to #28045 . Tested on CubeOrange (with artificially limited DNA database size) and a pile of MatekL431 boards with updated bootloaders. Not sure the policy on bootloader rebuilds.

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.
@@ -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.
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;
} else {
} else if (msg.node_id != CANARD_BROADCAST_NODE_ID) { // new ID valid? (if not we will time out and start over)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

i don't think this wins anything, just costs flash, the set of bcast is OK, and we stay in DNA

Copy link
Contributor Author

@tpwrules tpwrules Oct 8, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Currently having msg.node_id equal to CANARD_BROADCAST_NODE_ID would cause libcanard to execute CANARD_ASSERT(false);: https://github.com/dronecan/libcanard/blob/6f74bc67656882a4ee51966c7c0022d04fa1a3fb/canard.c#L122

Sure by default the assert doesn't do anything, but it's not really correct to do and the same change was accepted for #28045. We are already careful to not pass that value:

if (initial_node_id != CANARD_BROADCAST_NODE_ID) {
canardSetLocalNodeID(&canard, initial_node_id);
}

Copy link
Contributor Author

@tpwrules tpwrules Oct 8, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I checked and it only consumes flash on one periph.

@tridge tridge merged commit 4df758f into ArduPilot:master Oct 8, 2024
44 checks passed
@tpwrules tpwrules deleted the pr/boot-reject-bad-nodeid branch October 8, 2024 00:52
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants