Technical Article – ArduPilot F9P RTK

Overview

When DJI discontinued the Phantom 4 Pro V2 RTK, I decided it was time to implement RTK myself on an ArduPilot quad copter. The Hexsoon EDU-450 is almost identical in size to the Phantom – so I decided to start with that platform.

There is straight forward ArduPilot and CubePilot documentation for implementing RTK using the CubePilot Here2 and Here3. According to the posts and articles I’ve read, many have implemented it successfully. Both the Here2 and Here3 use u-Blox 8th generation GNSS receivers. I decided that if I were going to invest the time and effort into implementing RTK, it was worth the extra effort of implementing it with uBlox 9th generation receiver. I chose the popular u-Blox F9P.

The F9P RTK rover I’d built to mark ground control points provided the necessary components for the GNSS receiver for the Mission Planner RTK base. And with access to an Ntrip caster service, I could evaluate both using both my own GNSS base and Ntrip.

Both implementations were successful.

There were a number of unexpected technical challenges I had to work through to achieve this success. This article addresses them. The primary challenges were F9P firmware and settings, and SiK telemetry radio configuration.

Equipment Selection and Installation

The first step was choosing a suitable RTK capable F9P receiver. The CubePilot HerePro would have been my first choice but it is unavailable – and quite expensive. Holybro was my second choice – there were two models I considered – the H-RTK F9P Rover Lite, and the H-RTK F9P Helical.

The H-RTK F9P Rover Lite is a round saucer shaped device similar to the Here3. Both use a patch antenna. H-RTK F9P Rover Lite receiver is 57 grams heaver than the Here3 – and uses the Pixhawk 10 pin GH connector that includes leads for the buzzer. The CubePilot carrier board’s GPS connections use 8 pin GH connectors without support for the buzzer. The H-RTK F9P Helical is essentially the same weight (0.2 grams heavier) as the Here3 – but has a helical antenna promising better reception. The photo below shows the two Holybro receivers together. I first tried them both in non-RTK operation – both worked well.

Both Holybro receivers required replacing the 10 pin GH connector with an 8 pin. This job was a bit tricky on the H-RTK F9P Rover Lite because the provided harness was encased in plastic. Fortunately, each wire was a different color – making it easier to keep the wires in the proper order on the new connector.

There is a drawback to having to change the connector. Holybro provides a very nice UART to USB converter with the H-RTK F9P Rover Lite. The converter uses the 10 pin GH connector – so once I switched to the 8 pin GH connector I had to swap back again to use the converter. I may fabricate an 8 pin to 10 pin converter.

Once the Holybro H-RTK F9P Helical was installed I flew several non-RTK test flight to verify it worked properly. These test flights were successful. The F9P acquired up to 32 satellites and achieved an HDOP of 0.5.

DGPS mode was reported by telemetry. This indicates receiving SBAS satellite connections and accuracy of about 1 meter. The ArduPilot data logs reports this mode in the GPS.status parameter. The GPS.status values are:

  • 3D – GPS.status=3
  • DGPS – GPS.status=4
  • RTK FLOAT – GPS.status=5
  • RTK FIXED – GPS.status=6

Initial Test Flights

The non-RTK test flights demonstrated good performance for the H-RTK F9P Helical receiver. It would easily lock 29 satellites or more and achieve acceptably low HDOP. There is limited sky visibility in my yard (tall trees) where I conducted my initial tests – so I considered this good performance.

Attaching my ArduSimple F9P receiver to Mission Planner for an RTK base was easy and presented no problems. I simply followed the ArduPilot and CubePilot Here+ Base documentation. Mission Planner reported achieving an accuracy of 0.5 meters in about 20 minutes at my yard with tall trees, and only 10 minutes in an open field.

The copter went into RTK mode as soon as the SiK radio telemetry link was established between the Mission Planner base and the copter.

Testing RTK at just a meter or two altitude in my wooded yard seemed to work OK – getting an occasional GPS glitch indicated by the “GPS Bad Health” warning. I attributed this to signal interference due to the tall trees in my yard. To verify this I flew straight up in Loiter to 100 meters – clear of the trees.

The result was a cascade of GPS glitches that resulted in an EKF Failsafe.

This occurrence was eye-opening on many fronts. When the event happened, all I knew was that the warning “Bad GPS Health” was persistent and I noticed on my Yappu Mavlink message display that a EKF lane switch and failsafe had occurred. I didn’t realize that the copter had switched to Land mode. Because I considered the possibility of doing a “toilet bowl” in Loiter, I switched modes to Altitude Hold – and safely landed the copter.

Three things caught my attention in my initial attempt to understand what happened:

  • Since Copter 3.3 there is no failsafe setting for GPS – it’s now part of the EKF failsafe.
  • There are three available EKF failsafe options – set in the parameter: FS_EKF_ACTION. They are: Land, Altitude Hold, and Land Even in Stabilize. The default is Land, which is what my copter did. (I’ve changed my EKF failsafe now to Altitude Hold)
  • If a failure in RTK operations can cause an EKF failsafe, then RTK operations poses a real risk to flight safety.
This graph shows the altitudes and flight modes for this flight incident.

Problem Investigation and Identification

After doing initial investigation searching the forums and documents, I posted the problem in the discuss.ardupilot.org forum.

The initial exchanges on this message thread centered on the basic elements of the telemetry link and the F9P firmware and parameters. The message thread is available for anyone wanting to read the details.

Early in the investigation I made sure that the F9P receivers (base and rover) were updated to the latest release – 1.32. Yuri Rage on the discuss.ardupilot.org mentioned that doing the “reset parameters to default” procedure had cured some GPS problems for him. I mistakenly thought that installing new firmware would automatically reset all parameters to their defaults. I’ve learned that there is a way to do this – but apparently I hadn’t done it.

I don’t recall the exact symptoms that improved once I did the parameter reset procedure – but it’s an important step either when loading firmware or as the extra step afterwards.

One respondent on the message thread properly identified the primary root cause. Unfortunately I was too busy testing other theories to give it attention. Luckily, a response to a post I made on the u-Blox Support Portal contained the same advice – along with some additional helpful suggestions.

At this point the problem resolution has two elements – F9P parameter setting changes, and improvements to my SiK radio telemetry. While the key issue was with F9P parameter settings, that didn’t become clear until late into the investigation. My initial trouble shooting revolved around the SiK radio telemetry – which needed attention, but wasn’t the root cause of the problem.

The Root Cause – F9P Parameter Changes

Had I charted the GPA.DELTA parameter in the log file for the test flight where the EKF failsafe occurred, I would have seen this:

Click to enlarge

The GPA.delta log file parameter displays the time interval between GPS messages. This rate is set by the parameter GPS_RATE_MS and it defaults to 200ms – 5hz. The EKF warning GPS Bad Health is generated when GPS messages fail to arrive fast enough. (I don’t remember the specific threshold, but I recall seeing it somewhere.)

ArduPilot EKF3 has a threshold for sensor errors that cause it to lane switch. (switch to a different IMU). The GPS is one of these sensors. I haven’t seen reference to the threshold, but if the GPS message rate is slow enough and for long enough, it will cause an EKF Lane switch, and potentially a EKF Failsafe. In my case the GPS message rate never exceeded 400ms. It seems to me that this threshold alone is too low to cause EKF recovery actions.

Comments to two of my threads on separate support forums identified the solution. To prevent delays in receiving GPS messages I needed to limit the F9P on the copter to two constellations and disable SBAS. This is accomplished with the parameters: GPS_GNSS_MODE and GPS_SBAS_MODE.

In addition there is a note in the release notes for u-Blox firmware release 1.32 that says that the message rate cannot exceed 7hz with 4 constellations. Perhaps the u-Blox 9th generation receivers have processing limitations that cause this restriction. I still can’t explain why I didn’t have any issues with this in non-RTK operation using 4 constellations.

Once I set the ArduPilot parameters for the receiver to use only the GPS and GLONASS constellations and disabled SBAS I was able to set the rate up to 10hz and achieve reliable rates.

Click to enlarge

Secondary Cause – SiK Radio Implementation

My post on discuss.ardupilot.org got a response regarding the high transmission buffer shown in the flight’s log. The response suggested that at close to 100% TxBuffer some of the RTK corrections may not be getting through.

TxBuf on test flight with EKF Failsafe – Click to enlarge

Going through my SiK telemetry radios setup I made the following “tune-up” improvements:

  • Updated the SiK radio firmware.
  • Increased the Air Data Rate and Baud Rate parameters
  • Changed my ground station connection to reduce USB noise
  • Replaced my copter’s SiK radio’s short 2 dBi monopole antennas with 2 of the longer 3 dBi dipole antennas.

Although I believe my telemetry radio integrity is now far more robust, I don’t see the TxBuf statistics changing significantly for the better.

Interestingly, I was able to duplicate another person’s report that corrections sent from a base using Ntrip corrections put less load on the TxBuf than the base using corrections from a F9P receiver.

TxBuf from Base Using Ntrip

Updating the firmware on my RFDesigns RFD900x radios took a couple of attempts because the RFDesigns firmware website has the latest firmware listed in the section listed “RFD SiK Compliant” and some other version in the section listed “RFD SiK”. I assumed my RFD900x’s are the real thing – so I first loaded the firmware in the “RFD SiK” section. The other section had the newest firmware.

Click to enlarge

The only way I found my mistake was that I have both V1 and V2 versions of the RFD900x. They only connect if the V1 radios have the latest firmware.

There isn’t much information about the SiK radio settings. The Baud Rate setting only affects the connection between the radio and it’s host. (the autopilot or the ground control station) Increasing the Baud Rate only increases bandwidth if the data rate between the radios is higher – and that’s set with the Air Data Rate parameter. I set the Baud Rate to 115200 and the Air Data Rate to 125. (125000)

It was never clear to me what the Max Window setting changed. The default value is 131. However this value isn’t available on the configuration screens. The only way I could set it to 131 was to take the option to set all the parameters to their defaults – and then update the other settings as necessary. When I made parameter changes in a different order, the Max Window went to 20 – its minimum setting.

Using ECC and the re-transmit options drastically reduce bandwidth – so I didn’t use them.

In addition to bandwidth that may take up 100% of the TxBuf, the SiK radios are susceptible to noise. A primary source of noise is USB equipment. Before this project I only used an Android tablet and Qgroundcontrol with my telemetry radios. USB noise didn’t seem to be an issue. But the Microsoft Surface and Docking Station that I’m using with Mission Planner as an RTK base seems to emit lots of USB noise.

To reduce the noise I mounted my RFD900x on a tripod several feet from the ground station computer, and stopped using my Bask Aerospace AeroLink Base case because it includes USB circuitry. Instead I used the RFDesgns FDTI cable – which is fairly long.

The results of these improvements can be seen in the RSSI and Noise graphs. Note that the RxErrors rate is reduced by half.

The last change I made was to replace my copter’s telemetry radio’s antenna. I had been using the small monopole antennas that need a ground plane to function best. I’m now using the longer dipole antennas. They provide better gain and do not require a ground plane.

Summary

With the changes to the F9P settings and SiK radio set-up, I’m now able to fly RTK missions where the copter goes quickly to RTK-Fixed mode after power up, and stays the entire flight. With only two constellations there are only half as many satellites possible as in non-RTK mode. Unfortunately to change the number of constellations requires changing the parameters manually. It would be handy if this change could happen automatically when switching from RTK to non-RTK operation. And I get equally good performance using Ntrip as an F9P receiver as my RTK base.

Successful RTK Flight
Video taken during the flight charted above.

One thought on “Technical Article – ArduPilot F9P RTK

  1. I am really intrigued as to how you got the H-RTK F9P working on the Cube Orange? – I am struggling at the moment for the GPS data to be seen in MIssion Planner (show no GPS data, yet I know there is data coming out of UART1)

    What are the cubepilot settings that you are using for the serial ports for the GPS1 and GPS2?

    Thanks
    Tom

Leave a Reply

Your email address will not be published. Required fields are marked *