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
@dakejahl dakejahl force-pushed the pr-restore-CANNODE_NODE_ID branch from d0a92b7 to 58a6260 Compare October 14, 2025 19:59
@dakejahl dakejahl marked this pull request as ready for review October 14, 2025 20:05
dakejahl
dakejahl previously approved these changes Oct 14, 2025
Copy link
Contributor

@dakejahl dakejahl left a comment

Choose a reason for hiding this comment

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

Tested on a couple of our CAN products. Verified setting CANNODE_NODE_ID allows the user to configure the Node ID. If this is later set back to 0 (ID is allocated) the flight controller will continue to allocate that same ID (this is how DNA works). Verified firmware updating continues to work.

Users must take care to avoid configuring two nodes with the same ID.

Need to add docs now.

@dakejahl dakejahl self-assigned this Oct 14, 2025
Copy link

/en/dronecan/ark_cannode.md

  • LinkedFileMissingAnchor: #CANNODE_NODE_ID not found in ../advanced_config/parameter_reference.md (/home/runner/work/PX4-Autopilot/PX4-Autopilot/docs/en/advanced_config/parameter_reference.md)

/en/dronecan/ark_flow.md

  • LinkedFileMissingAnchor: #CANNODE_NODE_ID not found in ../advanced_config/parameter_reference.md (/home/runner/work/PX4-Autopilot/PX4-Autopilot/docs/en/advanced_config/parameter_reference.md)

/en/dronecan/ark_flow_mr.md

  • LinkedFileMissingAnchor: #CANNODE_NODE_ID not found in ../advanced_config/parameter_reference.md (/home/runner/work/PX4-Autopilot/PX4-Autopilot/docs/en/advanced_config/parameter_reference.md)

/en/dronecan/ark_gps.md

  • LinkedFileMissingAnchor: #CANNODE_NODE_ID not found in ../advanced_config/parameter_reference.md (/home/runner/work/PX4-Autopilot/PX4-Autopilot/docs/en/advanced_config/parameter_reference.md)

/en/dronecan/ark_rtk_gps.md

  • LinkedFileMissingAnchor: #CANNODE_NODE_ID not found in ../advanced_config/parameter_reference.md (/home/runner/work/PX4-Autopilot/PX4-Autopilot/docs/en/advanced_config/parameter_reference.md)

/en/dronecan/index.md

  • LinkedFileMissingAnchor: #CANNODE_NODE_ID not found in ../advanced_config/parameter_reference.md (/home/runner/work/PX4-Autopilot/PX4-Autopilot/docs/en/advanced_config/parameter_reference.md)
  • LinkedFileMissingAnchor: #CANNODE_NODE_ID not found in ../advanced_config/parameter_reference.md (/home/runner/work/PX4-Autopilot/PX4-Autopilot/docs/en/advanced_config/parameter_reference.md)

/en/dronecan/px4_cannode_fw.md

  • LinkedFileMissingAnchor: #CANNODE_NODE_ID not found in ../advanced_config/parameter_reference.md (/home/runner/work/PX4-Autopilot/PX4-Autopilot/docs/en/advanced_config/parameter_reference.md)
  • LinkedFileMissingAnchor: #CANNODE_NODE_ID not found in ../advanced_config/parameter_reference.md (/home/runner/work/PX4-Autopilot/PX4-Autopilot/docs/en/advanced_config/parameter_reference.md)

@dakejahl dakejahl requested a review from hamishwillee October 14, 2025 20:31
@AlexKlimaj
Copy link
Member Author

In its current state, it will only use the static ID if no ID was allocated on boot. We discussed overriding that if the static ID is set. What do you think?

@DronecodeBot
Copy link

This pull request has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there:

https://discuss.px4.io/t/px4-dev-call-oct-15-2025-team-sync-and-community-q-a/47650/1

}

// Assign the static node ID if no dynamic allocation is used. Do wen't override a valid node ID from the bootloader?
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.

Suggested change
if (node_id == 0 && cannode_node_id > 0 && cannode_node_id <= 127) {
if (node_id == 0 && cannode_node_id > 0 && cannode_node_id <= uavcan::NodeID::Max) {

param_get(param_find("CANNODE_NODE_ID"), &cannode_node_id);

// Check if the static node ID is in range
if (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.

Suggested change
if (cannode_node_id < 0 || cannode_node_id > 127) {
if (cannode_node_id < 0 || cannode_node_id > uavcan::NodeID::Max) {

// Persist the node ID for the bootloader
bootloader_app_shared_t shared_write = {};
shared_write.node_id = node_id;
shared_write.bus_speed = bitrate;
Copy link
Member

Choose a reason for hiding this comment

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

There's not really any error checking or validation on the bitrate, it might be safer to do this a bit later after the node has actually started spinning successfully.

For example you could do it here, and only if there was no dynamic node ID allocation. https://github.com/AlexKlimaj/PX4-Autopilot/blob/a4064072c793787aa9aac149c376bbf3c613d8b0/src/drivers/uavcannode/UavcanNode.cpp#L558-L580

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Projects

None yet

Development

Successfully merging this pull request may close these issues.

4 participants