Skip to content
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

AP_GPS: added GPS_DRV_OPTIONS for fully parsing RTCMv3 injection #26317

Merged
merged 3 commits into from
Mar 6, 2024

Conversation

tridge
Copy link
Contributor

@tridge tridge commented Feb 24, 2024

This adds full RTCM parsing of incoming RTCM injection if it sees RTCM coming in on more than one MAVLink channel.
This allows for setups where you have redundency in comms links, such as is common for light show drones which may inject RTCM data via both WiFi and a SiK radio setup as receive only
This also gets RTCM logging at the message ID level, allowing you to debug RTCM injection issues with a lot more detail
Two new GPS_DRV_OPTIONS are added:

  • one to enable this RTCM full parse even for a single channel (useful for extra logging for debugging)
  • one to disable the automatic full RTCM decode for multi-channel (in case users want to inject non-RTCM data or data that our RTCM parser can't handle)

Copy link
Collaborator

@andyp1per andyp1per left a comment

Choose a reason for hiding this comment

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

LGTM, just one comment

Tools/AP_Periph/gps.cpp Outdated Show resolved Hide resolved
@IamPete1
Copy link
Member

Any reason we should not do this by default?

@tridge
Copy link
Contributor Author

tridge commented Feb 27, 2024

maybe we should automatically enable this if we see GPS RTCM packets on more than 1 MAVLink channel?

libraries/AP_GPS/AP_GPS.h Outdated Show resolved Hide resolved
@tridge
Copy link
Contributor Author

tridge commented Feb 27, 2024

pending testing from @ntamas and @andyp1per

@tridge
Copy link
Contributor Author

tridge commented Feb 29, 2024

Any reason we should not do this by default?

I've now made it automatic when it sees RTCM on multiple channels. It can be disabled with the option (for the case where users are injecting non-RTCM data)

@tridge tridge added the WikiNeeded needs wiki update label Feb 29, 2024
@ntamas
Copy link
Contributor

ntamas commented Feb 29, 2024

Tested the latest version today (only in the lab yet, with a pre-recorded RTCM stream) and it seemed to work well! It was slightly confusing that injection on one channel only does not trigger the writing of the RTCM log entries - I understand why that happens (I needed to set GPS_DRV_OPTIONS to 64), but it should be documented somewhere for the RTCM log entries so people won't start looking for the log entries if they have a single channel only.

I also had to #include "AP_GPS_config.h" in AP_GPS.h in our fork (based on ArduCopter 4.4.x) because AP_GPS.h refers to AP_GPS_RTCM_DECODE_ENABLED and its default value comes from AP_GPS_config.h.

@ntamas
Copy link
Contributor

ntamas commented Feb 29, 2024

One more comment: GPA.RTCMFU and GPA.RTCMFD seem to be redundant / misleading now. When the fragment goes through the RTCMv3 parser, it never reaches handle_gps_rtcm_fragment() so the rtcm_stats.fragments_used counter never gets incremented.

@tridge
Copy link
Contributor Author

tridge commented Mar 4, 2024

One more comment: GPA.RTCMFU and GPA.RTCMFD seem to be redundant / misleading now

we could have a separate RTCM message broken out of GPA for that use case, but I don't think it is worth it

with newer receivers, RTCMv3 packets can be larger than 300
this allows for redundent RTCM links (eg. WiFi and SiK links for light
show drones) without causing corruption into the GPS.

If the GPS_DRV_OPTION bit is set then we instantiate a separate RTCM3
decoder per mavlink channel, and only inject when we get a full packet
that passes the RTCM 24 bit CRC
@ntamas
Copy link
Contributor

ntamas commented Mar 6, 2024

@tridge We tested the injection with 20 drones and two simultaneous channels last Thursday and everything worked fine, thank you!

I'm leaning towards patching the Skybrush branch to always have bit 6 set in GPS_DRV_OPTIONS for sake of consistency of behaviour irrespectively of the number of channels used by the operator, though. It makes automated log analysis and support easier for us if we don't have to consider the legacy RTCM injection mechanism.

Copy link
Contributor

@rmackay9 rmackay9 left a comment

Choose a reason for hiding this comment

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

The two new driver options are pretty esoteric but most users won't need to understand or change them and from testing it seems they're required so fine with me.

@tridge tridge merged commit 0f6f738 into ArduPilot:master Mar 6, 2024
89 checks passed
@andyp1per
Copy link
Collaborator

Very nice work @tridge! Also amazed at how quickly you knocked this together

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
GPS WikiNeeded needs wiki update
Projects
Status: 4.5.0-beta3
Development

Successfully merging this pull request may close these issues.

6 participants