Skip to content

Conversation

AlexKlimaj
Copy link
Member

This PR adds back the CANNODE_NODE_ID param for setting a static node ID on cannodes. This will need careful testing as the last time I dove into this, ran into too many edge cases that could prevent a node from booting.

@AlexKlimaj
Copy link
Member Author

@dakejahl @dagar @davids5

@dagar dagar self-requested a review October 1, 2025 15:28
@dagar dagar requested a review from dakejahl October 1, 2025 15:33
int32_t cannode_node_id = 0;
param_get(param_find("CANNODE_NODE_ID"), &cannode_node_id);

if (node_id == 0 && cannode_node_id > 0 && cannode_node_id <= 127) {
Copy link
Member

Choose a reason for hiding this comment

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

At a minimum we should probably print an error if the node ID value isn't valid.

cannode_node_id = 0;
}

// Assign the static node ID if no dynamic allocation is used. Do wen't override a valid node ID from the bootloader?
Copy link
Member Author

Choose a reason for hiding this comment

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

This setup will use the dynamic ID from the bootloader, do we want to override it?

Copy link
Contributor

Choose a reason for hiding this comment

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

Yes I think if the user has specified a static node ID via CANNODE_NODE_ID and it does not match the NodeID from the shared memory then we need to override it, print a warning, and update the value in shared memory.

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