Extend SENS_GPS_PRIME usage for UAVCAN GNSS devices#26126
Conversation
🔎 FLASH Analysispx4_fmu-v5x [Total VM Diff: 552 byte (0.03 %)]px4_fmu-v6x [Total VM Diff: 560 byte (0.03 %)]Updated: 2026-01-07T09:31:08 |
MaEtUgR
left a comment
There was a problem hiding this comment.
Why aren't all GPS instances published as they are available and the sensor module selects like how it is done for every sensor and GNSS modules until now? This pr scrambles the responsibility of selecting the primary GNSS module over sensors module and UAVCAN driver by making assumptions about the uORB instance order which is not guaranteed depending on advertising order which can be seen from the lengthy error messages in the code.
I assume sensor_gps.device_id contains the UAVCAN node ID in some way and that's how e.g. magnetometers get prioritized. Why do it completely different for GNSS receivers?
39593a7 to
9507095
Compare
|
@MaEtUgR Thanks for the feedback and pointers, i've rewrote it into a much nicher implementation |
dakejahl
left a comment
There was a problem hiding this comment.
Thanks for the fix. Going forward we should try to move away from using "instances" of things. We should instead favor device_id, and then we don't need to map between the two.
src/modules/sensors/vehicle_gps_position/VehicleGPSPosition.cpp
Outdated
Show resolved
Hide resolved
src/modules/sensors/vehicle_gps_position/VehicleGPSPosition.cpp
Outdated
Show resolved
Hide resolved
MaEtUgR
left a comment
There was a problem hiding this comment.
Much much nicer!! Thanks for trying out the suggested architecture 🙏 🙏
The only thing I'd still improve is to only read the parameter and set the primary GPS in one place. It's now not only on parameter changes that the function setPrimaryInstance() can get called and it just increases complexity to do that in two places making assumptions about the range. But everything is at a much higher level now 🙏
|
Btw, your PR also fixes this old bug that I have forgotten to follow up 👍
|
|
We should probably also clearly specify the behavior if the parameter is set to an ID that isn't connected to the system. For example if a GNSS receiver is swapped so that there are two instances, but none match the specified id. I would believe this to be a pretty common situation. Ideally, this should at least provide some sort of warning? |
067d165 to
6fc57a7
Compare
|
No flaws found |
|
@Claudio-Chies looks like you've got some of the latest commits from main tangled up in here. For syncing with main I would suggest using the |
6fc57a7 to
0ce1bbf
Compare
|
@dakejahl yea i hate the update branch functionality from the WebUI, it tends to mess things up afterwards. |
|
@dakejahl should be ready to merge now, had to fix a casting issue. |
Co-authored-by: Matthias Grob <maetugr@gmail.com>
Co-authored-by: Øyvind Taksdal Stubhaug <o_github@oystub.com>
Co-authored-by: Matthias Grob <maetugr@gmail.com>
8b6f708 to
9e5802f
Compare
* UAVCAN: extent SENS_GPS_PRIME usage to UAVCAN GNSS devices * use convenience function Co-authored-by: Matthias Grob <maetugr@gmail.com> * Update src/drivers/uavcan/sensors/gnss.cpp Co-authored-by: Øyvind Taksdal Stubhaug <o_github@oystub.com> * Apply suggestion from @MaEtUgR Co-authored-by: Matthias Grob <maetugr@gmail.com> * Fix type casting in GPS prime range check * UAVCAN: fix and improve device_id logic * Added bus information to more UAVCAN drivers * Fix device_id registration in UavcanBarometerBridge --------- Co-authored-by: Matthias Grob <maetugr@gmail.com> Co-authored-by: Øyvind Taksdal Stubhaug <o_github@oystub.com> Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
Solved Problem
When using multiple UAVCAN GNSS modules, users were not able to set the primary one as they would be able to with serial modules
Solution
With this i extend the usage of the SENS_GPS_PRIME to GNSS devices, whereby the parameter now works as follows:
-1 : Auto (equal priority for all instances)
0 : Main serial GPS instance
1 : Secondary serial GPS instance
2-127 : UAVCAN module node ID
also changed the default behavior to be automatic. because a default value of 0 with an all UAVCAN setup is not ideal.
Changelog Entry
For release notes:
Limitations
the only limiation is that the GNSS module cant have static NodeID 1, which is a valid NodeID bus is usualy the autopilot
Test coverage