-
Notifications
You must be signed in to change notification settings - Fork 14.6k
Add back CANNODE_NODE_ID for setting a static node ID #25669
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
base: main
Are you sure you want to change the base?
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change | ||||
---|---|---|---|---|---|---|
|
@@ -824,6 +824,27 @@ extern "C" int uavcannode_start(int argc, char *argv[]) | |||||
} | ||||||
} | ||||||
|
||||||
// Read the static node ID parameter and use it if no valid node_id from shared memory | ||||||
int32_t cannode_node_id = 0; | ||||||
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) { | ||||||
PX4_ERR("Invalid static node ID %ld, using dynamic allocation", cannode_node_id); | ||||||
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? | ||||||
dakejahl marked this conversation as resolved.
Show resolved
Hide resolved
|
||||||
if (node_id == 0 && cannode_node_id > 0 && cannode_node_id <= 127) { | ||||||
dakejahl marked this conversation as resolved.
Show resolved
Hide resolved
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
node_id = cannode_node_id; | ||||||
} | ||||||
|
||||||
// Persist the node ID for the bootloader | ||||||
bootloader_app_shared_t shared_write = {}; | ||||||
shared_write.node_id = node_id; | ||||||
shared_write.bus_speed = bitrate; | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe 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 |
||||||
bootloader_app_shared_write(&shared_write, BootLoader); | ||||||
|
||||||
if ( | ||||||
#if defined(SUPPORT_ALT_CAN_BOOTLOADER) | ||||||
board_booted_by_px4() && | ||||||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.