Skip to content

Conversation

@Claudio-Chies
Copy link
Member

@Claudio-Chies Claudio-Chies commented Dec 16, 2025

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:

Feature: Extended SENS_GPS_PRIME for UAVCAN GNSS devices

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

  • Tested with 2 Serial GNSS Modules
  • Tested with 1 Serial, 1 UAVCAN module, where the Serial had priority
  • Tested with 1 Serial, 1 UAVCAN module, where the UAVCAN had priority
  • Tested with 2 UAVCAN Modules, where both were connected at start
  • Tested with 2 UAVCAN Modules, where the one with priority was connected a few seconds after boot.

@github-actions
Copy link

github-actions bot commented Dec 16, 2025

🔎 FLASH Analysis

px4_fmu-v5x [Total VM Diff: 144 byte (0.01 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.0%    +144  +0.0%    +144    .text
  +4.7%     +72  +4.7%     +72    UavcanGnssBridge::process_fixx<>()
   +12%     +36   +12%     +36    sensors::VehicleGPSPosition::Run()
   +36%     +20   +36%     +20    uavcan::ReceivedDataStructure<>::safeget<>()
  +0.0%      +8  +0.0%      +8    [section .text]
  +0.0%      +8  +0.0%      +8    g_cromfs_image
  +5.5%      +6  +5.5%      +6    sensors::VehicleGPSPosition::ParametersUpdate()
  +0.6%      +4  +0.6%      +4    uavcan::Publisher<>::broadcast()
  -8.3%      -2  -8.3%      -2    sensors::VehicleGPSPosition::Start()
  -0.6%      -4  -0.6%      -4    UavcanGnssBridge::gnss_fix2_sub_cb()
  -6.7%      -4  -6.7%      -4    matrix::Vector<>::norm()
+0.0%    +376  [ = ]       0    .debug_abbrev
+0.0%     +16  [ = ]       0    .debug_aranges
+0.0%     +32  [ = ]       0    .debug_frame
+0.0% +1.59Ki  [ = ]       0    .debug_info
+0.0%    +280  [ = ]       0    .debug_line
 -20.0%      -1  [ = ]       0    [Unmapped]
  +0.0%    +281  [ = ]       0    [section .debug_line]
-0.0%     -31  [ = ]       0    .debug_loclists
-0.0%     -81  [ = ]       0    .debug_rnglists
 -66.7%      -2  [ = ]       0    [Unmapped]
  -0.0%     -79  [ = ]       0    [section .debug_rnglists]
+0.4%      +1  [ = ]       0    .shstrtab
+0.0%    +291  [ = ]       0    .strtab
 -37.2%     -16  [ = ]       0    __arm_switchcontext_veneer
  +100%     +16  [ = ]       0    __memset_veneer
   +46%    +291  [ = ]       0    uavcan::ReceivedDataStructure<>::safeget<>()
+0.0%     +64  [ = ]       0    .symtab
   +33%     +16  [ = ]       0    ___ZNK3Ekf21updateAidSourceStatusI24estimator_aid_source3d_sN6matrix7Vector3IfEES4_EEvRT_RKyRKT1_RKT0_SE_SE_f.isra.0_veneer
 -40.0%     -32  [ = ]       0    __arm_switchcontext_veneer
   +67%     +32  [ = ]       0    __memset_veneer
 -25.0%     -16  [ = ]       0    __nxsem_wait_irq_veneer
 -33.3%     -16  [ = ]       0    __nxsig_lowest_veneer
   +50%     +16  [ = ]       0    __stm32_i2c_setclock_veneer
 -33.3%     -16  [ = ]       0    sensors::VehicleGPSPosition::ParametersUpdate()
  +100%     +16  [ = ]       0    sensors::VehicleGPSPosition::Start()
 -20.0%     -16  [ = ]       0    uavcan::DynamicArrayBase<>::validateRange()
   +62%     +80  [ = ]       0    uavcan::ReceivedDataStructure<>::safeget<>()
-1.4%    -144  [ = ]       0    [Unmapped]
+0.0% +2.51Ki  +0.0%    +144    TOTAL

px4_fmu-v6x [Total VM Diff: 160 byte (0.01 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.0%    +160  +0.0%    +160    .text
  +4.7%     +72  +4.7%     +72    UavcanGnssBridge::process_fixx<>()
   +12%     +36   +12%     +36    sensors::VehicleGPSPosition::Run()
  +0.0%     +24  +0.0%     +24    g_cromfs_image
   +36%     +20   +36%     +20    uavcan::ReceivedDataStructure<>::safeget<>()
  +0.0%      +8  +0.0%      +8    [section .text]
  +5.5%      +6  +5.5%      +6    sensors::VehicleGPSPosition::ParametersUpdate()
  +0.6%      +4  +0.6%      +4    uavcan::Publisher<>::broadcast()
  -8.3%      -2  -8.3%      -2    sensors::VehicleGPSPosition::Start()
  -0.6%      -4  -0.6%      -4    UavcanGnssBridge::gnss_fix2_sub_cb()
  -6.7%      -4  -6.7%      -4    matrix::Vector<>::norm()
+0.0%    +376  [ = ]       0    .debug_abbrev
+0.0%     +16  [ = ]       0    .debug_aranges
+0.0%     +32  [ = ]       0    .debug_frame
+0.0% +1.59Ki  [ = ]       0    .debug_info
+0.0%    +280  [ = ]       0    .debug_line
 -20.0%      -1  [ = ]       0    [Unmapped]
  +0.0%    +281  [ = ]       0    [section .debug_line]
-0.0%     -31  [ = ]       0    .debug_loclists
-0.0%     -81  [ = ]       0    .debug_rnglists
  [DEL]      -2  [ = ]       0    [Unmapped]
  -0.0%     -79  [ = ]       0    [section .debug_rnglists]
-1.3%      -3  [ = ]       0    .shstrtab
+0.0%    +291  [ = ]       0    .strtab
   +46%    +291  [ = ]       0    uavcan::ReceivedDataStructure<>::safeget<>()
+0.0%     +64  [ = ]       0    .symtab
 -33.3%     -16  [ = ]       0    sensors::VehicleGPSPosition::ParametersUpdate()
  +100%     +16  [ = ]       0    sensors::VehicleGPSPosition::Start()
 -20.0%     -16  [ = ]       0    uavcan::DynamicArrayBase<>::validateRange()
   +62%     +80  [ = ]       0    uavcan::ReceivedDataStructure<>::safeget<>()
+100% +3.84Ki  [ = ]       0    [Unmapped]
+0.0% +6.51Ki  +0.0%    +160    TOTAL

Updated: 2025-12-19T07:24:31

Copy link
Member

@MaEtUgR MaEtUgR left a comment

Choose a reason for hiding this comment

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

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?

@Claudio-Chies
Copy link
Member Author

@MaEtUgR Thanks for the feedback and pointers, i've rewrote it into a much nicher implementation

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.

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.

dakejahl
dakejahl previously approved these changes Dec 16, 2025
Copy link
Member

@MaEtUgR MaEtUgR left a comment

Choose a reason for hiding this comment

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

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 🙏

Comment on lines +139 to +142
if (device_id.devid_s.bus_type == device::Device::DeviceBusType_UAVCAN
&& device_id.devid_s.address == static_cast<uint8_t>(gps_prime)) {
_gps_blending.setPrimaryInstance(i);
}
Copy link
Contributor

Choose a reason for hiding this comment

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

Is there any reason to restrict this to only DroneCAN devices? If we use the full device id struct/uint32, it could match any GPS device. I don't see why this setting should assume a specific bus type.

Maybe it's slightly more advanced to set up, but I think anyone manually assigning DroneCAN IDs is an advanced enough user that they can find the full device ID of the GNSS receiver.

Copy link
Member Author

Choose a reason for hiding this comment

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

@oystub
for Serial GPS devices its already handled in the existing implementation. this is just an extension of that functionality to DroneCAN devices. or am i missing your point?

Copy link
Contributor

@oystub oystub Dec 17, 2025

Choose a reason for hiding this comment

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

	struct DeviceStructure {
		DeviceBusType bus_type : 3;
		uint8_t bus: 5;    // which instance of the bus type
		uint8_t address;   // address on the bus (eg. I2C address)
		uint8_t devtype;   // device class specific device type
	};

	union DeviceId {
		struct DeviceStructure devid_s;
		uint32_t devid{0};
	};

Also, since the 8 MSB are free, there isn't any problem having all possible IDs fit in a signed int32 parameter. (edit: which is obviously the case with how we do mag/imu calibration ids anyway)

Copy link
Contributor

Choose a reason for hiding this comment

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

@Claudio-Chies Assume a DroneCAN GNSS receiver with node id 125.

I think it would be nicer to set the parameter to 8748291, which represents:
Bus Type: 3 (UAVCAN), Bus: 0, Address: 125, DevType: 0x85 (DRV_GPS_DEVTYPE_UAVCAN)

Then, the additional logic doesn't have to be coupled specifically to dronecan, and it could be used to set any device to primary.

Copy link
Contributor

@oystub oystub Dec 17, 2025

Choose a reason for hiding this comment

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

IMO this is nicer than handling serial and DroneCAN devices separately, and would also work with things like MAVLink or simulation GNSS receivers.

Technically DRV_MAG_DEVTYPE_HMC5883=1 but since bustype 0 represents DeviceBusType_UNKNOWN, I think it works well to keep the 0 and 1 values to mean instance ids, and anything larger device ids.

(And it allows all possible DroneCAN IDs, even 1)

Copy link
Member Author

Choose a reason for hiding this comment

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

i do agree that this would more uniquely specify which device, but how would you then surface this to the user in the GCS? to encode all that info into binary is not really user friendly. or the question would be if that would avoid conflicts which could not be avoided in this setup. (aside from the obvious NodeID1).
then two GPS's with the same node id on separate buses would be possible, is the main thing which comes to my mind.

Copy link
Contributor

@oystub oystub Dec 17, 2025

Choose a reason for hiding this comment

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

My suggestion is to just have the raw device ID as a user parameter, e.g. 8748291, like for the mag calibration IDs. But one would have to run sensors status or look at a log to easily find this ID. However, I completely agree that this is a tradeoff between "ease of use for the most common use case" and clean architecture (not having a special case for uavcan). I think most people that want to use this feature, probably also understand device IDs well enough to set it, even if it uses the full device id.

The "same node id, different buses" would also apply to magnetometer calibration btw, if we start populating the "bus" field, as suggested in #26135. So it is kind of already something to consider, even if we keep this field as a "simple" node id.

Copy link
Contributor

Choose a reason for hiding this comment

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

We could improve the output of uavcan status to show more information

Sensor 'gnss':
name: uavcan_gnss
channel 0: node id 116 --> instance 0
channel 1: node id 52 --> instance 1

We could show full device_id and breakdown of what it means

Copy link
Contributor

Choose a reason for hiding this comment

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

If we're going to switch from instance to device_id let's do that in another PR. This is a good intermediate step.

@oystub
Copy link
Contributor

oystub commented Dec 17, 2025

Btw, your PR also fixes this old bug that I have forgotten to follow up 👍

BUG: When using multiple DroneCAN GNSS sensors, they all get the same device id, as the id is stored in a variable shared by all sensor_gps channels.

#22880

@oystub
Copy link
Contributor

oystub commented Dec 17, 2025

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?

@github-actions
Copy link

No flaws found

@dakejahl
Copy link
Contributor

@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 rebase command git rebase main which will apply each of your commits onto main and prompt you to resolve merge conflicts per-commit. If you have a lot of commits on a branch this can quickly become totally ineffective. In that case you should first squash your commits into a single commit .using git reset HEAD~N where N is the number of commits and then git add . && git commit -m "blah". After you squash you can then run git rebase main and you will only have to resolve merge conflicts once. Alternatively you can do git merge main and avoid force pushing, this mixes your commits in with main but that's okay because we squash-and-merge anyway.

Claudio-Chies and others added 3 commits December 19, 2025 08:15
Co-authored-by: Matthias Grob <maetugr@gmail.com>
Co-authored-by: Øyvind Taksdal Stubhaug <o_github@oystub.com>
@Claudio-Chies
Copy link
Member Author

@dakejahl yea i hate the update branch functionality from the WebUI, it tends to mess things up afterwards.
should be clean now

Co-authored-by: Matthias Grob <maetugr@gmail.com>
Comment on lines +139 to +142
if (device_id.devid_s.bus_type == device::Device::DeviceBusType_UAVCAN
&& device_id.devid_s.address == static_cast<uint8_t>(gps_prime)) {
_gps_blending.setPrimaryInstance(i);
}
Copy link
Contributor

Choose a reason for hiding this comment

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

If we're going to switch from instance to device_id let's do that in another PR. This is a good intermediate step.

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.

5 participants