GPS F9P Module Setup¶
This guide covers connecting the SparkNavi F9P RTK GPS module to SparkNavi Blue, the ArduPilot parameters that matter, and — more importantly — why each parameter is set the way we recommend. For full hardware specifications, see the SparkNavi F9P product page.
1. What You Need¶
- 1 × SparkNavi F9P module (or 2 × for dual-GPS / RTK Yaw setups)
- 1 × multi-band L1/L2/E5b antenna (antenna choice drives real-world accuracy more than anything else)
- Stock GPS cables shipped with SparkNavi Blue
- Mission Planner running on Windows (or QGroundControl)
2. Wiring¶
SparkNavi Blue exposes two GPS ports: GPS1 (8-pin) and GPS2 (6-pin). Both share the same I²C2 bus, which is what allows the BMM150 compass on each F9P module to be auto-detected.
| Signal | F9P pin | Blue GPS1 pin | Blue GPS2 pin |
|---|---|---|---|
| +5 V | 1 | 1 | 1 |
| UART RX | 2 | 2 (TX) | 2 (TX) |
| UART TX | 3 | 3 (RX) | 3 (RX) |
| I²C SCL | 4 | 4 | 4 |
| I²C SDA | 5 | 5 | 5 |
| GND | 6 | 8 | 6 |
On GPS1, pins 6 and 7 (safety switch + LED) are left disconnected when wiring an F9P module.
3. ArduPilot Parameters¶
For a single F9P on GPS1:
| Parameter | Value | Notes |
|---|---|---|
GPS1_TYPE |
2 |
u-blox driver |
GPS_AUTO_CONFIG |
3 |
Recommended — see §4 |
GPS_AUTO_SWITCH |
1 |
Use best fix |
GPS_PRIMARY |
0 |
GPS1 |
For dual F9P (two identical modules on GPS1 + GPS2):
| Parameter | Value | Notes |
|---|---|---|
GPS1_TYPE / GPS2_TYPE |
2 / 2 |
Both u-blox |
GPS_AUTO_CONFIG |
3 |
Same as single — see §4 |
GPS_AUTO_SWITCH |
2 |
Blend — see §4 |
GPS_INJECT_TO |
127 |
Broadcast RTCM to both for RTK |
After writing parameters, reboot the flight controller.
4. Why These Settings¶
This is the part most setup guides skip. Here is the reasoning behind the recommended values.
Why GPS_AUTO_CONFIG = 3¶
ArduPilot's default GPS_AUTO_CONFIG = 1 configures serial GPS modules at boot using ArduPilot's known-good defaults, but it does not clear any pre-existing custom configuration written to the u-blox module via u-center. On u-blox Generation 9 modules — which the ZED-F9P is — residual config from a previous setup (different baud rate, different message rates, RTCM filters) can interact unpredictably with what ArduPilot is trying to do.
Setting GPS_AUTO_CONFIG = 3 tells ArduPilot to first clear any non-ArduPilot configuration in the module, then apply its defaults. The result is a deterministic, repeatable boot state — which matters when a module gets swapped between aircraft or when a unit comes back from the field with unknown history.
Why GPS_AUTO_SWITCH = 2 (Blend) for two identical F9P modules¶
The blend mode is designed for the case where both GPSes are of the same type and produce solutions of comparable quality. With two identical F9P units pulling from the same constellations and (with RTCM injection) the same correction stream, their solutions are statistically equivalent. Averaging them suppresses uncorrelated transient errors on either unit — a small but consistent precision improvement.
This is fundamentally different from a mixed setup like F9P + M8N. There, the F9P is decisively better and you do not want to average it down with the weaker unit; GPS_AUTO_SWITCH = 4 (use primary if 3D fix) is the right choice in that case.
EKF3 jamming mediation (EK3_OPTIONS bit 0)¶
For platforms that may operate in RF-contested environments — defense, near military airspace, near high-power broadcast or radar emitters — enabling EK3_OPTIONS bit 0 changes EKF3's behavior on GPS recovery. Instead of immediately consuming the GPS solution as soon as it locks back, the preflight GPS quality checks must pass again first. This prevents a deliberately corrupted GPS signal from being re-trusted by the navigation filter.
What this option is not
This protects across short jamming events followed by GPS recovery. It is not a substitute for GPS-denied navigation. Sustained GPS denial requires optical flow + rangefinder, visual-inertial odometry, or external position injection.
5. SparkNavi Blue–Specific Notes¶
A few things specific to running F9P on Blue that aren't obvious from generic ArduPilot docs:
Both BMM150 compasses share I²C2. When two F9P modules are connected to Blue, both onboard BMM150 magnetometers appear on the same bus with different I²C addresses. ArduPilot auto-discovers both as external compasses. SparkNavi Blue has no internal compass, so the two BMM150s become the primary and secondary compass automatically — no need to disable internal compasses manually.
Compass priority — pick the one farther from noise. With two external compasses, set COMPASS_PRIO1_ID to the device ID of the BMM150 mounted physically farther from the ESCs, power wires, and high-current paths. The IDs appear in Mission Planner's compass setup screen. This is the single biggest improvement you can make to yaw stability on a multirotor with two GPS modules.
Stock cabling is correct. The cables shipped with Blue are wired for direct 1-to-1 connection — no rewiring needed. If you are sourcing your own cables (e.g. for a custom airframe), follow the pin table in §2.
6. Verification¶
After wiring, parameter write, and reboot, in Mission Planner check:
- 3D fix within ~30 seconds outdoors with clear sky
- Sat count 20–30+ (multi-constellation reception is the F9P's strength)
- HDOP < 1.0 within a minute
- For RTK: RTK Float then RTK Fixed within ~35 seconds once RTCM corrections are flowing
If you see 3D fix but not RTK Fixed with corrections active, the most common cause is GPS_INJECT_TO not being set to 127.
7. Troubleshooting¶
| Symptom | Likely cause |
|---|---|
| No GPS detected | Cable orientation reversed, or GPS1_TYPE = 0 |
| 3D fix but very high HDOP | Antenna placement — too close to carbon fiber, or no clear sky |
| Stuck at "RTK Float" | Antenna is single-band, or correction stream isn't multi-band |
| Compass FAILED in pre-arm | COMPASS_ORIENT doesn't match GPS module's physical mounting direction |