Raspberry Pi based PPK and RTK solutions with RTKLIB

It’s been over six years now since I published my last post on how to run RTKLIB on a Raspberry PI, so it’s more than time for an update. In my previous post, I described using a Pi Zero as a data logger for a u-blox M8N for PPK solutions. In this post I will work with a Pi Model 4 and a u-blox M8T to demonstrate both logging for PPK solutions and a real-time RTK solution. The good news is that this time no soldering is required since we are going to use the USB port on the Pi to connect the receiver. These instructions will work with any u-blox receiver that supports raw observations and any model Pi that has USB ports for peripherals. With minor modifications, they can be used with any receiver that has a USB or UART port and supports raw observations.

Here’s an image of the assembled setup. The Pi in the center, and the u-blox M8T receiver is on top. We will use a wireless connection to talk to the Pi from an external computer so there is no need for a keyboard or display.

Raspberry Pi with u-blox M8T receiver


Step 1: Configure the Pi

The first step is to configure the Pi in “headless” mode so that we can talk to it from an external computer. This is quite straightforward and well-explained in this post, so I will not describe how to do it here. Only steps 1 and 2 in the post are required for this exercise. If you plan to use this for RTK solutions, be aware that the Pi will rely on the wireless connection to the internet for base station observations. This means that if you don’t want to be limited to using it within range of your home wireless router, then you will probably want to connect to a hot spot from a cell phone. If you are just interested in collecting data for PPK solutions, then it doesn’t matter.

After you have completed steps 1 and 2 above, you should have a Putty window open and have logged into your Pi. The next step is to build and install the RTKLIB code. The commands below will clone the RTKLIB code from the Github repository, compile the stream server app (str2str) and the RTK solution app (rtkrcv), and copy the executables to a location where they can be accessed from any directory.

> sudo apt update
> sudo apt install git
> mkdir rtklib
> cd rtklib
> git clone https://github.com/rtklibexplorer/RTKLIB.git
> cd RTKLIB/app/consapp/str2str/gcc
> make
> sudo cp str2str /usr/local/bin/str2str
> cd ../../rtkrcv/gcc
> make
> sudo cp rtkrcv /usr/local/bin/rtkrcv
> cd ../../../../..


Step 2: Configure the receiver

Before we connect the u-blox receiver to the Pi, we will need to configure it to output raw observation and navigation messages. The easiest way to do this is from your computer with the u-center app which can be downloaded from the u-blox website. Connect the receiver to your computer with a USB cable, start u-center, and connect to the receiver using the “Connection” option in the “Receiver” tab as shown in the image below.

u-center: Connect to receiver

Next, use the “Messages View” window from the “View” menu to enable the RAWX and SFRBX messages as seen below. While you are in the messages view, you can also disable any unnecessary NMEA messages to save communication bandwidth.

u-center: Enable raw observation and navigation messages


Next, we will switch to the “Configuration View” window to configure any other desired settings and then save them to flash . I would recommend verifying that all constellations are enabled with the “GNSS” command and that the sample rate is set to the desired value with the “RATE” command. I usually set this to 5 Hz. I would also recommend disabling both UART ports with the “PORT” command if you are not using them. If the baud rates are set too low, they will limit bandwidth on all ports including the USB port, even if nothing is connected to those ports. Finally, use the “CFG” command to save the settings to flash as shown below.

u-center: Save settings to flash

Step 3: Verify the data stream(s)

Next, we will confirm that we are receiving data from the rover receiver and if running a real-time solution, also from the base receiver. This step is not absolutely essential, but it does verify that we have the individual pieces working before we put it all together, and also gives some practice using the RTKLIB str2str command.

Disconnect the rover receiver from the computer and connect it to the Pi using a USB cable as shown in the image at the top of this post. Enter the following commands into the Putty console to create a new folder and run the stream server. This will connect to the USB port on the Pi. If you are using a UART port, you will need to use the appropriate port name.

> mkdir data
> cd data
> str2str -in serial://ttyACM0

The output of the receiver should now scroll across the Putty console screen. If you have any NMEA messages enabled, you should be able to see them mixed in with a bunch of random characters from the binary messages. Once you’ve confirmed the data stream, hit Control C to stop it.

If we want to log the receiver output for a PPK solution, we just need to add a file name to the previous command to redirect the data stream from the screen to a file. The command below will do this, using keywords in the file name to create a name that includes the current month, day, hour, and minute.

> str2str -in serial://ttyACM0 -out rover_%m%d_%h%M.ubx

The image below shows the expected output of both commands.

Verification of receiver data stream

If you are using the Pi just to log receiver data then you are done at this point unless you want to configure the Pi to make it automatically start collecting data whenever it is turned on. There are several ways to do this, all described in this post. Modifying the rc.local file is the simplest method.

For those who would prefer to run an RTK solution rather than just log data for a PPK solution, the next step is to confirm the base data stream. We will use the “str2str” command again, but this time we will specify the input to be an NTRIP stream using the format:

“ntrip://username:password@ipaddress:port/mountpoint”

In my case, the command looks like this: (with the username and password removed)

> str2str -in ntrip://username:password@rtgpsout.unavco.org:2101/P041_RTCM3: -out temp.log

If everything is working properly, you should see non-zero transfer numbers and no errors, as in example above, in which case you can use Control C again to stop.

Note that if your NTRIP provider is using a VRS (Virtual Reference Station), then things are a little more complicated. We will need to send our local position inside of a GGA message. For this to work, you must have enabled the NEMA GGA message when configuring the receiver. To route these GGA messages back to the NTRIP server we will need to connect the stream server output to the receiver and enable the relay back feature with the “-b” option. Here’s an example I used to connect to test this with a VRS NTRIP server.

str2str -in ntrip://username:password@na.l1l2.skylark.swiftnav.com:2101/CRS -b 1 -out serial://ttyACM0

Step 4: Run the RTK solution

OK, now that we’ve confirmed that we are getting data from base and rover, it’s time to generate an RTK solution. We will use the “rtkrcv” console app in RTKLIB to do this, which we installed in Step 1.

We will need a configuration file for rtkrcv. You can use the “rtknavi_example.conf” file included with the demo5 release as a starting point but you will need to edit the stream configuration settings. Below are the settings I changed as well as a few important ones worth verifying are correct for your configuration. I have it configured to write the output to a file in LLH format. If you want the output in NMEA messages you can either change output stream 1 to “nmea” format or enable output stream 2 to get both a file and a stream of NMEA messages.

pos1-posmode =kinematic  # (0:single,1:dgps,2:kin,3:static)
pos1-frequency =l1  # (1:l1,2:l1+l2,3:l1+l2+l5)
pos1-navsys =13  # (1:gps+2:sbas+4:glo+8:gal+16:qzs+32:comp)
pos2-armode =fix-and-hold # (0:off,1:cont,2:inst,3:fix-and-hold)
pos2-gloarmode =fix-and-hold # (0:off,1:on,2:autocal,3:fix-and-hold)
out-solformat =llh #    (0:llh,1:xyz,2:enu,3:nmea)
ant2-postype =rtcm # (0:llh,1:xyz,2:sing,3:file,4:rinex,5:rtcm)
inpstr1-type =serial (0:off,1:ser,2:file,3:,...,7:ntrip)
inpstr2-type =ntripcli # (0:off,1:ser,2:file,3:,...,7:ntrip)
inpstr1-path =ttyACM0
inpstr2-path =usrname:pwd@rtgpsout.unavco.org:2101/P041_RTCM3
inpstr1-format =ubx # (0:rtcm2,1:rtcm3, ...)
inpstr2-format =rtcm3 # (0:rtcm2,1:rtcm3,...)
inpstr2-nmeareq =single # (0:off,1:latlon,2:single)
outstr1-type =file # (0:off,1:serial,2:file, ...)
outstr2-type =off # (0:off,1:serial,2:file, ...)
outstr1-path =rtkrcv_%m%d_%h%M.pos
outstr2-path =
outstr1-format =llh # (0:llh,1:xyz,2:enu,3:nmea)
outstr2-format =nmea # (0:llh,1:xyz,2:enu,3:nmea)
logstr1-type =file # (0:off,1:serial,2:file, ...)
logstr2-type =file # (0:off,1:serial,2:file, ...)
logstr1-path =rover_%m%d_%h%M.ubx
logstr2-path =base_%m%d_%h%M.rtcm3

I like to use WinSCP for editing and transferring files between the Pi and external computer but there are many other ways to do this. When you are done, the edited configuration file needs to be in the current folder you will run rtkrcv from. For my example, I renamed it “rtkrcv_pi.conf”

To run rtkrcv with a configuration file named “rtkrcv_pi.conf”, use the following commands:

> rtkrcv -s -o rtkrcv_pi.conf
  >> status  1

If all is well, you should see a status screen updated every second that looks something like this:



I changed the Putty display defaults to make this a little easier to read. I’ve also highlighted in yellow some of the numbers to check to make sure they look OK. Make sure you are seeing base RTCM location messages (usually 1005). If you want to check the input streams in more detail, you can use control c to exit the status menu, then enter “?” to see some of the other rtkrcv commands. To exit rtkrcv, use the “shutdown” command.

If all of your inputs look good, your solution is not working, and it is not obvious why, you can rerun rtkrcv with a “-t 3” in the command line. This will enable trace mode which will create a trace debug file which may offer clues as to what is wrong.

This should be enough to get you started. To explore more configuration options, see the str2str and rtkrcv sections in Appendix A of the RTKLIB users manual.


A first look at the u-blox ZED-F9T dual frequency receiver

Back in November last year, I wrote a post on my first experiments with a dual frequency u-blox F9P  based receiver.  At the time it was quite difficult for those without good connections to u-blox to get a hold of the F9P and even now, nearly three months later, it still is not readily available.  Ardusimple, the lowest price provider of F9P receivers still has all their receivers on back order till next month and low cost dual frequency antennas are even harder to get.  Hopefully all that will change fairly soon though.

Meanwhile, thanks to “clive1” and “cynfab” from the u-blox forum, I have been lucky enough to have been given a prototype receiver based on the dual frequency u-blox F9T, the next product from u-blox in the Generation 9 series.  Like the previous generation M8T, this is intended for timing uses and does not include an internal RTK engine.  Otherwise I believe the F9T hardware is nearly identical to the F9P.  In theory it should be less expensive than the F9P, just as the M8T is less expensive than the M8P but meaningful pricing is not yet available.

In many of my posts, I have focused on post-processing short baseline data sets using a local base station and identical receivers for base and rover.  For this particular  combination, I have shown that the differences between a single frequency solution and a dual frequency solution are typically fairly small.  This assumes that the single frequency solution includes Galileo and possibly SBAS while the dual-frequency solution includes only GPS and Glonass.  This makes the total number of observations fairly similar between the two cases.   At least until very recently this has been a reasonable assumption given that most existing CORS or other reference base stations and reasonably priced dual frequency receivers offered only GPS and Glonass.  It’s also true that time to first fix is longer in the single frequency solutions but post-processing with a combined solution generally eliminates the need for a fast fix.

However there are many other cases where there are definite advantages to using a dual frequency solution.  In particular the most important advantages occur for:

  • Longer baselines where linear combinations of L1 and L2 can cancel ionospheric errors
  • Use of an existing CORS or other reference base station which typically has only GPS and Glonass and hence is not an ideal match-up with a single frequency receiver using additional constellations
  • Real-time solutions where time to first fix is more critical
  • PPP (Precise Point Positioning) solutions for the same reasons as the long baseline cases.

So for my initial experiments with the F9T I focused on including some of these conditions.  In particular I ran two experiments, the first a real-time RTK solution with an existing UNAVCO reference base (P041) located 17 km away.  For the second experiment I compared an online PPP solution from the Canadian Spatial Reference System (CSRS) with an RTKLIB SSR based PPP solution.

For the first experiment, I connected the F9T receiver to the dual frequency antenna on my roof and ran a quick five minute RTKLIB real-time solution against the UNAVCO base station using the demo5 b31 RTKLIB code.  Other than changing the frequency mode from L1 to L1+L2 I used the exact same configuration file I normally use for the u-blox M8T single frequency receiver.  Even though the rover was stationary in this case, I ran the solution as kinematic for better visibility to any variation in the solution.  Here’s the result.

f9t_1

Overall the solution looked excellent.  First fix occurred within a few seconds, fix rate was 100% after first fix, horizontal variation was  roughly +/-0.5 cm and vertical variation was roughly +/-1 cm.

The solution residuals, both pseudorange and carrier-phase also looked very clean.

f9t_3

I only made a brief look at the raw observations but did not see anything unusual there either.  At only five minutes of data, it is not much more than a quick sanity check, but so far, so good.

For the second experiment I collected four hours of raw observations, again with the F9T receiver and my rooftop antenna, a ComNav AT330.  I then submitted this data to CSRS for their online PPP solution as well as running an RTKLIB SSR solution as I described in this post.  Below are the results for both solutions.  The plots are all relative to my best estimate of the location of the rooftop antenna based on previous PPP solutions with Swift and ComNav receivers as well as RTK solutions from nearby CORS stations.  The left plots shows the first hour of solution with a +/-0.25 meter vertical scale.  The right plot shows the second through fourth hours with a +/-0.06 meter vertical scale.

f9t_2

Both solutions get to below 6 cm of error in each axis after 1 hour and below 3 cm of error after four hours.  The CSRS solution gets down to almost zero error in all three axes after four hours but I don’t believe my reference is this accurate so I think this was partially luck.  The reported accuracies (95%) for the CSRS solution were 1 cm, 4 cm, and 5 cm for latitude, longitude, and height respectively.  My previous experience running RTKLIB SSR PPP solutions with other low cost dual frequency receivers is that after running many solutions, they generally all fall within +/-6 cm accuracies in all axes after four hours.  Both solutions include only GPS and Glonass observations because both the SSR correction stream I used from the CLK93 source, and the CSRS online PPP algorithm use only GPS and Glonass.

Being able to run accurate PPP static solutions can be a big advantage since it can make it much simpler to precisely locate a base station for RTK solutions with a dynamic rover, especially in more remote areas where there may not be any nearby CORS or other reference stations to run an RTK solution against.

As always, this post is intended to be just a quick snapshot and not an extended analysis of any type, but so far I have been very impressed with both the F9P and F9T and with their compatibility with RTKLIB.

 

 

A first look at the u-blox ZED-F9P dual frequency receiver

The new low cost dual frequency receiver from u-blox, the ZED-F9P, is just now becoming available for purchase for those not lucky enough to get early eval samples from u-blox.  CSGShop has a ZED-F9P receiver in stock for $260 which seems quite reasonable, given that it is only $20 more than their NEO-M8P single frequency receiver.

Even better, Ardusimple is advertising an F9P  receiver for 158 euros (~$180) + 20 euros shipping , although their boards won’t ship until January.  As far as I’m aware of, this is actually less than anybody today is selling the M8P receiver for today!

Of course, this is still a fair bit more than a u-blox M8T single frequency receiver without an internal RTK engine, which is available from CSGShop for $75, but the F9T will be coming out next year also without internal RTK engine, which should bring down the price for the lowest cost dual frequency receivers.

Unfortunately I am not one of the lucky ones who got eval boards directly from u-blox yet.  However, I do have two prototype boards from Gumstix, given to me by them for evaluation.  Gumstix offers both off-the-shelf boards and semi-custom boards designed from their libraries of circuits.  I haven’t worked with them directly but it looks like an interesting and useful concept.  The F9P boards from Gumstix won’t be available for sale until at least Feburary next year but I thought I would share the results of some initial testing.  From a performance perspective, I would expect these boards to be similar to F9P boards from other suppliers.

For a first look, I chose to compare the F9P to an M8T for one of my typical driving-around-the-neighborhood exercises.  I looked at both the internal real-time F9P solution and the RTKLIB solutions, both real-time and post-processed.

Experiment Setup:

For the base stations, I connected a CSGShop M8T receiver and a Gumstix F9P  receiver through an antenna splitter to a ComNav AT330 dual frequency antenna on my roof.  Since RTKLIB doesn’t yet fully support the receiver commands needed to setup the F9P, I used the most recent version (18.08) of the u-blox u-Center app run on a Windows laptop to configure the F9P receiver using the documentation on the u-blox website.  I then saved the settings to flash.  The receivers were connected to a laptop with USB cables and I broadcast the base observations over the internet on a couple of NTRIP streams using STRSVR and RTK2GO.com as I’ve described previously.  I configured the F9P to send RTCM3 1005, 1077, 1087, 1097, 1127, and 1230 messages which include base location, raw observations, and GLONASS biases.

For the most part the u-blox documentation is well written and this exercise was fairly straightforward, but I did run into a couple of issues.  First of all, when I plugged the F9P receiver into the laptop, Windows chose the standard Windows COM port driver instead of the u-blox GNSS COM port driver that it chose for the M8T receiver.  You can see this in the screen snapshot below where COM17 is the M8T and COM21 is the F9P.

drivers

Both drivers allow the user to set the baudrate in the properties menu available by right clicking on the device name.   With the u-blox driver, the baudrate setting doesn’t seem to matter which makes sense since it is a USB connection.  I have always left the u-blox driver baudrate at the default of 9600 baud without any issue.  With the windows driver, however,  I found that I had to increase the baudrate setting to 115200 to avoid data loss issues.  I have run into a similar problem before for sample rates greater than 5 Hz when the M8T is accessed through it’s UART interface and an FTDI converter is used to translate to USB, rather than communicating directly through it’s USB interface.  I verified though, that in this case the board is using the USB interface on the receiver and not the UART interface.   Not a big deal, and it may be unique to this board, but something to be aware of in case you run into a similar problem.

The second problem I ran into is that the F9P module seems to be sensitive to my antenna splitter, a standard SMA DC block and tee which I have used on many other receivers before without issue.  It works fine if the F9P power is blocked but if the M8T power is blocked, the F9P seems to detect the tee and shut off the antenna power.  Again, not a big deal, but something to be aware of.

For the rovers, I used a u-blox ANN-MB-00 dual-frequency antenna for the F9P receiver.  This is the antenna u-blox provides with its F9P eval units.  I had planned to split this antenna signal to both receivers as I usually do, but I ran into the problem described above, and not fully understanding the issue yet, ended up using a separate Tallysman TW4721 L1 antenna for the M8T receiver.  Both antennas were attached directly to the car roof which acted as a large ground plane.

I used a hot spot on my cellphone to stream the NTRIP base station observations from the phone to a laptop and then to the F9P receiver and to two instances of RTKNAVI, one for each rover receiver.

Streaming the base observations to the F9P, while simultaneously logging the internal RTK solution and the raw rover observations, and also sending the raw rover observations to RTKNAVI, all over a single serial port can be challenging since only a single application can be connected to the serial port at one time.  Fortunately RTKLIB has a little trick to deal with this.  If the “Output Received Stream to TCP Port” box is checked in STRSVR and a port number specified as shown below, all data coming from the other direction on the serial port will be redirected to a local TCP/IP port.  This data  can then be accessed by any of the other RTKLIB apps as a TCP Client with server address “localhost” using the specified port number.

str2str1

I set up the F9P rover to output both raw observation and navigation messages (UBX-RXM-RAWX/ UBX-RXM-SFRBX) and solution position messages( NMEA-GNGGA).  RTKNAVI then logged all of these messages to a single log file.  RTKCONV and RTKPLOT can both extract the messages they need from this file and ignore the rest so combining them was not an issue.

The NMEA-GNGGA messages from the F9P default to a resolution of 1e-7 degrees of latitude and longitude which works out to roughly 1 cm.  For higher resolution you can increase the resolution of the GNGGA message by setting a bit in the UBX-CFG-NMEA message.   Unfortunately I did not realize the resolution issue until after I collected the data and so my results for the internal F9P solution for this experiment were slightly deteriorated by the lower resolution.

I used the most recent demo5 b31 code to calculate all of the RTKLIB solutions.  Both the demo5 and the 2.4.3 versions of RTKLIB have been updated to translate the new dual frequency u-blox binary messages.  The demo5 solution code will process all the dual frequency observations but I don’t believe 2.4.3 code is able to process the E5b Galileo measurements yet.  The RTKLIB 2.4.2 code however does not have any of these updates.

The demo5 code updates made in the recent B30/B31 versions are based on the updates from the 2.4.3 B30 code but include some modifications to the u-blox cycle slip handling that I had previously added to the demo5 code for the M8T.  Since the demo5 code is primarily aimed at low cost receivers I also made some changes to make the E5b frequency a little easier to specify and faster to process.

To run the RTKNAVI F9P real-time solution, the only significant change I needed to make to the default M8T config file was to change the frequency option from “L1” to “L1+L2+E5b”.  I should have also changed the base station position to “RTCM Antenna Position” to take advantage of the F9 base station RTCM 1005 base location messages but neglected to do this.  This caused the RTKNAVI solution to differ from the F9P solution by small constant values due to the approximate base location used in the RTKNAVI solution.  I later used exact base locations for the RTKLIB post-processing solutions to verify that the different solutions did in fact all match.

Once I had everything set up, I then drove around the local neighborhood, emphasizing the streets with most challenging sky views since I knew both receivers would perform well and be difficult to distinguish if the conditions were not challenging enough.

Results:

I first converted the binary log files to observation files using RTKCONV and verified that the F9P was logging both L1 and L2 measurements for GPS, GLONASS, and Galileo.  I had the Bediou constellation enabled as well but as I verified later, there were no fully operational Bediou satellites overhead when I collected the data.

Here is an plot of the L1 observations for the M8T on the left and the F9P on the right.  I have zoomed into just two minutes during some of the more difficult conditions to compare the two.  The red ticks are cycle slips and the grey ticks are half cycle ambiguities.

f9_obs1

First, notice that the F9P does not log observations for the SBAS satellites, while the M8T does, giving the M8T a couple more satellites to work with.  However, what’s also interesting, and I don’t know why, is that the F9P collected quite good measurements from the Galileo E27 satellite, while the M8T did not pick up this one at all.  Of course the F9P also got a second set of measurements from the second frequency on each satellite and so overall ended up with nearly twice as many raw observations as the M8T.

Also notice that the F9P reports somewhat less cycle slips and many less half cycle ambiguities than the M8T.  Some of this might be because of the different antennas, but particularly the large difference in half cycle ambiguities suggests that u-blox has made other improvements to the new module besides just adding the second frequencies.

Another thing to notice is the number of Galileo satellites.  If you compare these plots to earlier experiments I’ve posted, you’ll notice there are more Galileo satellites now as more and more of them are starting to come online.  The extra satellites really help the M8T solutions because as you can see, they tend to have the highest quality observations through the most difficult times.  Again I don’t know why this is.  It doesn’t appear to be as true for the F9P though.

Next I looked at the real-time solutions.   First, the RTKLIB solutions with RTKNAVI for both receivers.  For the full driving route, the M8T solution had a 77.3% fix rate and the F9P solution had a 96.4% fix rate.  Here is a zoom into the most challenging part of the drive, an older neighborhood with narrower streets and larger trees, the M8T is on the left, and the F9P on the right.  Fixed solutions are in green and float in yellow.  Clearly here the F9P significantly outperformed the M8T.

f9_1

The F9P internal solution did even better with a 99.2% fix rate, as shown in the plot below.  All three solutions agreed within 2 cm horizontal, a little more in vertical, and none of them showed any sign of any false fixes.

f9_2

I didn’t do any static testing to characterize time to first fix as I sometimes do, but for this one run the RTKLIB time to first fix for the M8T was 18 seconds while the RTKLIB F9P solution reached first fix in 6 seconds.  In both cases, RTKLIB was started after the hardware had time to lock to the satellites and acquire navigation data for all satellites.  The demo5 RTKLIB code has an additional fix constraint based on the kalman filter position variance to minimize false fixes while the filter is converging and so this can sometimes affect time to first fix.  I had increased this parameter to 0.1 meter for this experiment since the large number of measurements reduces the chance of a false fix.  This constraint did not limit the M8T time to first fix but it did so for the F9P, meaning the F9P would have reached first fix even faster if this constraint were opened up more.   I can’t tell what the equivalent number would be for the internal F9P solution from this data since it had already been running and achieved a fix before I started logging the data but generally the F9P seems to acquire first fix very quickly.

Next I post-processed both data sets with RTKLIB using the combined-mode setting to run the kalman filter both forwards and backwards over the data.  This noticeably improved the results, bringing the fix rate for the M8T up from 77.3% to 96.1% and the F9P fix rate from 96.4% to 98.8%.

f9_3

Conclusion:

Obviously this is not enough data to make any definitive conclusions, but so far I am very impressed with the F9P!  Both the raw observations and the internal RTK solutions for the F9P look as good as anything I’ve seen from receivers costing many times what this one cost.

If anybody would like to look at the data from this experiment more closely, I have uploaded it to here.  I should mention that all the fix rates I specify in this post and other posts won’t exactly match the fix rates in the raw solutions, since I adjust the data start and end times to be consistent between data sets and to start after all solutions have achieved first fix.  I believe this is the fairest way to compare multiple solutions, especially when there is a mix of internal and RTKLIB solutions

Also, I’d like to thank Gumstix again for making these modules available to me for evaluation!

Update: 12/2/18:

Reviewing the config files I used for this experiment I discovered that, while I had intended the real-time and post-processing config files to be identical, there were in fact some small differences between them.  One difference in particular, that appears to have affected the results as described above, is that I reduced the minimum number of consecutive samples required to hold ambiguities (pos2-arminfix) from 100 to 20 for the post-processed config files.  A value of 100 corresponds to 20 seconds at the experiment’s 5 Hz sample rate which is a value I have typically used.  However, with lower ambiguity tracking gain (pos2-varholdamb=0.1) and the increase in observations coming from including Galileo, the chances of false fixes is reduced and I have been tending to use lower values of arminfix in more recent experiments.   Reducing this value appears to explain a large part of the jump in percent fix for the M8T between real-time and post-processing, rather than the switch from forward-only to combined that I attribute it to above.  These differences only affect the comparisons between RTKLIB real-time and post-processed results, and not between the M8T and the F9P since the config files were consistent between the two receivers.

This was only intended to be a quick first look at the F9P.  It will require more data and more analysis to properly characterize the F9P so I  won’t try to do that here but I will share the table shown below which includes a few cases I have run since the original post.  I hope to dig into the details in future posts.

Fix percent
Real-timePost-processPost-processPost-process
ARMIN=100ARMIN=100ARMIN=20ARMIN=20
forward-onlyforward-onlyforward-onlycombined
M8T/RTKLIB77.3%81.2%96.0%96.1%
F9P/RTKLIB96.4%99.1%99.3%98.8%
F9P internal99.2%

One last point worth making is that while at first glance the post-process fix percent increase from M8T=96.0% to F9P=99.3% may not sound that significant, it is in fact a factor of nearly six if you consider it as a decrease in float from 4.0% to 0.7%.

Updated guide to the RTKLIB configuration file

It’s been quite a while since I’ve updated my guide to the RTKLIB configuration file.  Since the last update I’ve added a couple of new features and learned a bit more about some of the existing features.  For previous updates,  I’ve just updated the original post, but this time I thought I would re-publish it to make it easier to find.

One of the nice things about RTKLIB is that it is extremely configurable and has a whole slew of input options available. Unfortunately these can be a bit overwhelming at times, especially for someone new to the software. The RTKLIB manual does briefly explain what each option does, but even with this information it can be difficult to know how best to choose values for some of the parameters.

I won’t try to give a comprehensive explanation of all the input options here, but will explain the ones I have found useful to adjust in my experiments and include a little about why I chose the values I did. I describe them as they appear in the configuration file rather than how they appear in the RTKNAVI GUI menu but the comments apply to both. I created this list by comparing my latest config files to the default config file and noting which settings were different. The values in the list below are the values I use in my config file for a 5 Hz rover measurement rate.  The same config files can be used for either RTKNAVI, RTKPOST, or RNX2RTKP.

The settings and options highlighted in blue below are available only in my demo code and not in the release code but otherwise much of what I describe below will apply to either code.  Most of my work is done for RTK solutions with Ublox M8N and M8T receivers and short baselines and these settings will more directly apply to these combinations but should be useful at least as a starting point for other scenarios.

This post is intended to be used as a supplement to the RTKLIB manual, not as a standalone document, so please refer to it for information on any of the input parameters not covered here.

SETTING1:

pos1-posmode = static, kinematic, static-start, movingbase, fixed

If the rover is stationary, use “static”. If it is moving, use “kinematic” or “static-start”. “Static-start” will assume the rover is stationary until first fix is achieved and then switch to dynamic mode, allowing the kalman filter to take advantage of the knowledge that the rover is not moving initially.  You can use “movingbase” if the base is moving as well as the rover, but it is not required unless the base is moving long distances.  I often find that “kinematic” gives better solutions than “movingbase” even when the base is moving.  “Movingbase” mode is not compatible with dynamics, so be sure not to enable both at the same time.  If the base and rover remain at a fixed distance apart, set “pos2-baselen” and “pos2-basesig” when in “movingbase” mode.   Use “fixed” if you know the rover’s exact location and are only interested in analyzing the residuals.

pos1-frequency = l1

“l1” for single frequency receivers,  “l1+l2” if the rover is dual frequency GPS/GLONASS/Bediou,  “l1+l2+e5b” if Galileo E5b is included.  Starting with the dem05 b33 code, Galileo E5b is included in the L2 solution, so “l1+l2” is equivalent to “l1+l2+e5b” 

pos1-soltype = forward, backward, combined

This is the direction in time that the kalman filter is run. For real-time processing, “forward” is your only choice. For post-processing, “combined” first runs the filter forward, then backwards and combines the results. For each epoch, if both directions have a fix, then the combined result is the average of the two with a fixed status unless the difference between the two is too large in which case the status will be float. If only one direction has a fix, that value will be used and the status will be fixed. If both directions are float then the average will be used and the status will be float. Results are not always better with combined because a false fix when running in either direction will usually cause the combined result to be float and incorrect. The primary advantage of combined is that it will usually give you fixed status right to the beginning of the data while the forward only solution will take some time to converge. The 2.4.3 code always resets the bias states before starting the backwards run to insure independent solutions. The demo5 code doesn’t reset the bias states to avoid having to lock back up when the rover is moving if ambiguity resolution is set to “continuous” but does reset them if it is set to “fix-and-hold”.  I only use the “backward” setting for debug when I am having trouble getting an initial fix and want to know what the correct satellite phase-biases are.

pos1-elmask = 15 (degrees)

Minimum satellite elevation for use in calculating position. I usually set this to 10-15 degrees to reduce the chance of bringing multipath into the solution but this setting will be dependent on the rover environment. The more open the sky view, the lower this value can be set to.

pos1-snrmask-r = off, pos1-snrmask-b = off,on

Minimum satellite SNR for rover (_r) and base(_b) for use in calculating position. Can be a more effective criteria for eliminating poor satellites than elevation because it is a more direct measure of signal quality but the optimal value will vary with receiver type and antenna type so I leave it off most of the time to avoid the need to tune it for each application.

pos1-snrmask_L1 =35,35,35,35,35,35,35,35,35

Set SNR thresholds for each five degrees of elevation. I usually leave all values the same and pick something between 35 and 38 db depending on what the nominal SNR is. These values are only used if pos1-snrmask_x is set to on.  If you are using dual frequencies, you will need to also set “pos1-snrmask_L2”

pos1-dynamics = on

Enabling rover dynamics adds velocity and acceleration states to the kalman filter for the rover. It will improve “kinematic” and “static-start” results, but will have little or no effect on “static” mode. The release code will run noticeably slower with dynamics enabled but the demo5 code should be OK. Be sure to set “prnaccelh” and “prnaccelv” appropriately for your rover acceleration characteristics.  Rover dynamics is not compatible with “movingbase” mode, so turn it off when using that mode.

pos1-posopt1 = off, on (Sat PCV)

Set whether the satellite antenna phase center variation is used or not. Leave it off for RTK but you set it for PPP. If set to on, you need to specify the satellite antenna PCV file in the files parameters.

pos1-posopt2 = off, on (Rec PCV)

Set whether the receiver antenna phase center variations are used or not. If set to on, you need to specify the receiver antenna PCV file in the files parameters and the type of receiver antenna for base and rover in the antenna section. Only survey grade antennas are included in the antenna file available from IGS so only use this if your antenna is in the file. It primarily affects accuracy in the z-axis so it can be important if you care about height. You can leave this off if both antennas are the same since they will cancel.

pos1-posopt5 = off, on (RAIM FDE)

If the residuals for any satellite exceed a threshold, that satellite is excluded. This will only exclude satellites with very large errors but requires a fair bit of computation so I usually leave this disabled.

pos1-exclsats=

If you know a satellite is bad you can exclude it from the solution by listing it here. I only use this in rare cases for debugging if I suspect a satellite is bad.

pos1-navsys = 7, 15,

I always include GLONASS and SBAS sats, as more information is generally better.  If using the newer 3.0 u-blox firmware with the M8T I also enable Galileo.

SETTING2:

pos2-armode = continuous, fix-and-hold

Integer ambiguity resolution method. “Continuous” mode does not take advantage of fixes to adjust the phase bias states so it is the most immune to false fixes.  “Fix-and-hold” does use feedback from the fixes to help track the ambiguities.  I prefer to use “fix-and-hold” and adjust the tracking gain (pos2-varholdamb) low enough to minimize the chance of a false fix.  If “armode” is not set to “fix-and-hold” then any of the options below that refer to holds don’t apply, including pos2-gloarmode.

pos2-varholdamb=0.001, 0.1 (meters)

In the demo5 code, the tracking gain for fix-and-hold can be adjusted with this parameter. It is actually a variance rather than a gain, so larger values will give lower gain. 0.001 is the default value, anything over 100 will have very little effect. This value is used as the variance for the pseudo-measurements generated during a hold which provide feedback to drive the bias states in the kalman filter towards integer values.  I find that values from 0.1 to 1.0 provides enough gain to assist with tracking while still avoiding tracking of false fixes in most cases.

pos2-gloarmode = on, fix-and-hold, autocal

Integer ambiguity resolution for the GLONASS sats.  If your receivers are identical, you can usually set this to “on” which is the preferred setting since it will allow the GLONASS sats to be used for integer ambiguity resolution during the initial acquire. If your receivers are different or you are using two u-blox M8N receivers you will need to null out the inter-channel biases with this parameter set to “fix-and-hold” if you want to include the GLONASS satellites in the AR solution. In this case the GLONASS sats will not be used for ambiguity resolution until after the inter-channel biases have been calibrated which begins after the first hold. There is an “autocal” option as well, but I have never been able to make this work in the 2.4.3 code.  In the demo5 code I have added the capability to this feature to preset the initial inter-channel bias, variance, and calibration gain.  I then set the biases to known values for the particular receiver pair and set the gain very low.  This defeats the auto calibration aspect of the feature but does provide a mechanism to specify the biases which is otherwise missing in RTKLIB.  When “autocal” is used, the GLONASS satellites will be used for the initial acquire.  The “autocal” feature can also be used to determine the inter-channel biases with a zero or short baseline using an iterative approach.

pos2-gainholdamb=0.01

In the demo5 code, the gain of the inter-channel bias calibration for the GLONASS satellites can be adjusted with this parameter. 

pos2-arthres = 3

This is the threshold used to determine if there is enough confidence in the ambiguity resolution solution to declare a fix. It is the ratio of the squared residuals of the second-best solution to the best solution. I generally always leave this at the default value of 3.0 and adjust all the other parameters to work around this one. Although a larger AR ratio indicates higher confidence than a low AR ratio, there is not a fixed relationship between the two. The larger the errors in the kalman filter states, the lower the confidence in that solution will be for a given AR ratio. Generally the errors in the kalman filter will be largest when it is first converging so this is the most likely time to get a false fix. Reducing pos2-arthers1 can help avoid this.  

pos2-arfilter = on

Setting this to on will qualify new sats or sats recovering from a cycle-slip. If a sat significantly degrades the AR ratio when it is first added, its use for ambiguity resolution will be delayed. Turning this on should allow you to reduce “arlockcnt” which serves a similar purpose but with a blind delay count.

pos2-arthres1 = 0.004-0.10

Integer ambiguity resolution is delayed until the variance of the position state has reached this threshold. It is intended to avoid false fixes before the bias states in the kalman filter have had time to converge. It is particularly important to set this to a relatively low value if you have set eratio1 to values larger than 100 or are using a single constellation solution. If you see AR ratios of zero extending too far into your solution, you may need to increase this value since it means ambiguity resolution has been disabled because the threshold has not been met yet. I find 0.004 to 0.10 usually works well for me but if your measurements are lower quality you may need to increase this to avoid overly delaying first fix or losing fix after multiple cycle slips have occurred.

pos2-arthres2

Relative GLONASS hardware bias in meters per frequency slot.  This parameter is only used when pos2-gloarmode is set to “autocal” and is used to specify the inter-channel bias between two different receiver manufacturers.  To find the appropriate values for common receiver types, as well as how to use this parameter for an iterative search to find values for receiver types not specified, see this post.  This parameter is defined but unused in RTKLIB 2.4.3

pos2-arthres3 = 1e-9,1e-7

Initial variance of the GLONASS hardware bias state.  This parameter is only used when pos2-gloarmode is set to “autocal”.  A smaller value will give more weight to the initial value specified in pos2-arthres2.  I use 1e-9 when pos2-arthres2 is set to a  known bias, and 1e-7 for iterative searches.  This parameter is defined but unused in RTKLIB 2.4.3

pos2-arthres4 = 0.00001,0.001

Kalman filter process noise for the GLONASS hardware bias state.  A smaller value will give more weight to the initial value specified in pos2-arthres2.  I use 0.00001 when pos2-arthres2 is set to a  known bias, and 0.001 for iterative searches.  This parameter is defined but unused in RTKLIB 2.4.3

pos2-arlockcnt = 0, 5  

Number of samples to delay a new sat or sat recovering from a cycle-slip before using it for integer ambiguity resolution. Avoids corruption of the AR ratio from including a sat that hasn’t had time to converge yet. Use in conjunction with “arfilter”. Note that the units are in samples, not units of time, so it must be adjusted if you change the rover measurement sample rate.  I usually set this to zero for u-blox receivers which are very good at flagging questionable observations but set it to at least five for other receivers.  If not using the demo5 RTKLIB code, set this higher since the “arfilter” feature is not supported.

pos2-minfixsats = 4

Minimum number of sats necessary to get a fix. Used to avoid false fixes from a very small number of satellites, especially during periods of frequent cycle-slips.

pos2-minholdsats = 5

Minimum number of sats necessary to hold an integer ambiguity result. Used to avoid false holds from a very small number of satellites, especially during periods of frequent cycle-slips.

pos2-mindropsats = 10

Minimum number of sats necessary to enable exclusion of a single satellite from ambiguity resolution each epoch.  In each epoch a different satellite is excluded.  If excluding the satellite results in a significant improvement in the AR ratio, then that satellite is removed from the list of satellites used for AR.

pos2-rcvstds = on,off

Enabling this feature causes the the measurement variances for the raw pseudorange and phase measurement observations to be adjusted based on the standard deviation of the measurements as reported by the receiver. This feature is currently only supported for u-blox receivers. The adjustment in variance is in addition to adjustments made for satellite elevation based on the stats-errphaseel parameter.  I generally get better results with this turned off.

pos2-arelmask = 15

Functionally no different from the default of zero, since elevations less than “elmask” will not be used for ambiguity resolution but I changed it to avoid confusion.

pos2-arminfix = 20-100  (5-20*sample rate)

Number of consecutive fix samples needed to hold the ambiguities. Increasing this is probably the most effective way to reduce false holds, but will also increase time to first hold and time to reacquire a hold.  As the ambiguity tracking gain is reduced (i.e. as pos2-varholdamb is increased), and the number of observations increases, arminfix can be reduced.  Note that this value should also be adjusted if the rover measurement sample rate changes.

pos2-elmaskhold = 15

Functionally no different from the default of zero, since elevations less than “elmask” will not be used for holding ambiguity resolution results but I changed it to avoid confusion.

pos2-aroutcnt = 100 (20*sample rate)

Number of consecutive missing samples that will cause the ambiguities to be reset. Again, this value needs to be adjusted if the rover measurement sample rate changes.

pos2-maxage = 100

Maximum delay between rover measurement and base measurement (age of differential) in seconds. This usually occurs because of missing measurements from a misbehaving radio link. I’ve increased it from the default because I found I was often still getting good results even when this value got fairly large, assuming the dropout occurred after first fix-and-hold.

pos2-rejionno = 1000, 0.2

Reject a measurement if its pre-fit residual is greater than this value in meters. I have found that RTKLIB does not handle outlier measurements well, so I set this large enough to effectively disable it. With non-ublox receivers which typically are not as good at flagging outliers, I sometimes have to set this back to the default of 30 or even lower to attempt to handle the outliers but this is a trade-off because it can then cause other issues, particularly with initial convergence of the kalman filter.

Outlier rejection has been improved in the demo5 code starting with version b33.  In addition to better handling of the outlier measurements, the way this number is applied to code and phase measurements has changed.  Previously this value was applied without adjustment to both code and phase measurements.  In the newer version, this value is still applied without adjustment to the phase measurements but is multiplied by eratio for the code measurements.  This allows it to be set to values appropriate for the phase measurements.  I usually set it to 0.2 which is very helpful to catch and reject unflagged cycle slips.

OUTPUT:

out-solformat = enu, llh, xyz

I am usually interested in relative distances between rover and base, so set this to “enu”. If you are interested in absolute locations, set this to “llh” but make sure you set the exact base location in the “ant2” settings. Be careful with this setting if you need accurate z-axis measurements. Only the llh format will give you a constant z-height if the rover is at constant altitude. “Enu” and “xyz” are cartesian coordinates and so the z-axis follows a flat plane, not the curvature of the earth. This can lead to particularly large errors if the base station is located farther from the rover since the curvature will increase with distance.

out-outhead = on

No functional difference to the solution, just output more info to the result file.

out-outopt = on

No functional difference to the solution, just output more info to the result file.

out-outstat = residual

No functional difference to the solution, just output residuals to a file. The residuals can be very useful for debugging problems with a solution and can be plotted with RTKPLOT as long as the residual file is in the same folder as the solution file.  

stats-eratio1 = 300
stats-eratio2  = 300

Ratio of the standard deviations of the pseudorange measurements to the carrier-phase measurements. I have found a larger value works better for low-cost receivers, but that the default value of 100 often work better for more expensive receivers since they have less noisy pseudorange measurements. Larger values tend to cause the kalman filter to converge faster and leads to faster first fixes but it also increases the chance of a false fix. If you increase this value, you should set pos2-arthres1 low enough to prevent finding fixes before the kalman filter has had time to converge. I believe increasing this value has a similar effect to increasing the time constant on a pseudorange smoothing algorithm in that it filters out more of the higher frequencies in the pseudorange measurements while maintaining the low frequency components.

stats-prnaccelh = 3.0

If receiver dynamics are enabled, use this value to set the standard deviation of the rover receiver acceleration in the horizontal components. This value should include accelerations at all frequencies, not just low frequencies. It should characterize any movements of the rover antenna, not just movements of the complete rover so it may be larger than you think. It will include accelerations from vibration, bumps in the road, etc as well as the more obvious rigid-body accelerations of the whole rover.  It can be estimated by running a solution with this value set to a large value, then examining the accel values in the solution file with RTKPLOT

stats-prnaccelv = 1.0

The comments about horizontal accelerations apply even more to the vertical acceleration component since in many applications the intentional accelerations will all be in the horizontal components. It is best to derive this value from actual GPS measurement data rather than expectations of the rigid-body rover. It is better to over-estimate these values than to under-estimate them.

ant2-postype = rinexhead, llh, single

This is the location of the base station antenna. If you are only interested in relative distance between base and rover this value does not need to be particularly accurate. For post-processing I usually use the approximate base station location from the RINEX file header. If you want absolute position in your solution, then the base station location must be much more accurate since any error in that will add to your rover position error. If I want absolute position, I first process the base station data against a nearby reference station to get the exact location, then use the ”llh” or “xyz”option to specify that location. For real-time processing, I use the “single” option which uses the single solution from the data to get a rough estimate of base station location.

ant2-maxaveep = 1

Specifies the number of samples averaged to determine base station location if “postype” is set to “single”. I set this to one to prevent the base station position from varying after the kalman filter has started to converge since that seems to cause long times to first fix. In most cases for post-processing, the base station location will come from the RINEX file header and so you will not use this setting. However if you are working with RTCM files you may need this even for post-processing.

MISC:

misc-timeinterp =off,on

Interpolates the base station observations.  I generally set this to “on” if the base station observations sample time is larger than 5 seconds.

Please help me update this list if you have had success adjusting other options or using different settings for these options, or if you disagree with any of my suggestions. I will treat this as a working document and continue to update it as I learn more.

Event logging with RTKLIB and the u-blox M8T receiver

Event logging is a nice feature that has been available in the Emlid version of RTKLIB for a long time.  In the latest version of the demo5 code (b29e), I have ported this feature from their open-source code repository.  Their version is specifically for the u-blox M8T receiver but I have extended it to support the Swiftnav receiver as well.  I mentioned this feature in my previous post and had a couple requests for more information, hence this post.

Both the u-blox and Swiftnav receivers have hardware/firmware to capture the precise time an external pin changes state and send out a binary message with this information.  The RTKLIB event logging code decodes these messages and logs the events to the rinex file.  The events in the rinex file are then used in post-processing to generate a position log containing an interpolated position for each timing event. The most popular use for this feature is probably to record camera shutter times but it can also be used for other purposes such as marking survey locations in the data stream.

Here is an example of a drone flight from a data set containing events that I downloaded from the Emlid forum.  On the left is the ground track of the standard position solution plotted with RTKPLOT.  It includes one point for every rover observation epoch.  On the right is a plot of the event positions from the new event position file.  In this case there is one point for every event which gives precise locations for each camera image.  This is very useful information when processing the images.

event1

Here are the positions of the two plotted on top of each other, green dots are the rover observation epochs from the position file and the blue dots are the events from the event position file.  As you can see from the plot, the event positions are interpolated from the observation epochs.

event4

 

There is information in the Emlid and Swiftnav documentation on how to connect an external trigger to their hardware so I won’t cover that here.

Instead, I will go through an example using an M8T receiver from CSGShop.  I will also use this example to try and validate this feature since there has been some discussion on the Emlid forum about potential issues that as far as I can tell have not been completely resolved on the forum.

The CSGShop M8T receiver comes in several variations.  To use event logging you will need to choose a board that provides access to the external interrupt pins.  You can use either EXINT0 or EXINT1.  For this experiment I also use the TIMEPULSE pin to provide triggers for the event logging.  Here is an image of the receiver and the interface pins.

event9

The goal of this experiment is to generate events for which I know their precise timing so I can use them to validate the RTKLIB event logging results.  To do this, I configured the M8T TIMEPULSE output for a period of two seconds and a falling edge that occurs at 0.2 seconds, all in GPST time.  I then connected the TIMEPULSE output pin to the EXTINT1 input pin so that each state change of the output pulse will be recorded as an event.  Although the M8T will record both rising edges and falling edges, RTKLIB is setup to record only the falling edges.

To configure the timing pulse, I used the u-blox u-center app to setup the UBX-CFG-TP5 command as shown below.

event2

I then enabled the UBX-TIM-TM2 messages which the receiver uses to output the event information.  Next, I opened the table view in u-center and configured it to log GPS time, and the rise and fall times for EXTINT1.  This information is extracted from GPRMC and TIM-TM2 messages.  As you can see the falling edges of the pulse are occurring at exactly 0.2 seconds on the even seconds in GPS time so it looks like we have correctly configured the output pulse

event3

Now that I have external events occurring at precisely known times, I can use these to test the RTKLIB code.   The u-blox example command files that I include with the demo5 executables already are setup to enable the UBX-TIM-TM2 messages, so there is no need to make any changes there.

The next step is to collect some base and rover data using the modified receiver as rover.  I did that, and then converted the raw .ubx files to rinex using the new demo5 version of RTKCONV.  The events appear with a time stamp followed by a 5 in the next field to indicate an external event as shown below.  The zero in the last field indicates it is a valid time mark.

event5

The observation epochs are occurring every second, so notice that the event is being logged out of sequence with a one sample delay.  I did not see this with the Emlid data set example described above.  However, I do see the same delay  if I use the Emlid code to convert the binary file instead of my code.  I don’t know if the Emlid hardware has somehow been configured to avoid this sequencing issue or whether it can occur on the Emlid hardware as well.  I’ll get back to this in a minute.

Next I ran RTKPOST to calculate a position solution.  With the new code changes, a *.events.pos file is generated in addition to the *.pos file.  It is the same format as the *.pos file but contains the event positions instead of the observation epoch positions.  Note, that it will be generated for absolute solutions (XYZ,LLH) LLH but not for relative (ENU) solutions.

I first did this with the Emlid code and got the following result when plotting both the position file and event position file.

event6

The events are occurring at the correct times, but note that unlike the previous example, the positions are not being correctly interpolated between the two closest observation epochs.  In fact, if you look carefully you will see they are being extrapolated from the two previous observation epochs.  This is most obvious in the N-S axis points and is occurring because the events are being logged out of sequence.

To fix this, I modified the interpolation code to use the nearest observation epochs even when the event logging was delayed by one sample.  Here is the result using the latest demo5 b30 code.

event7

Looking at the time stamps from the position log and the event position log, shown below, you can see that the observation epochs are occurring on the integer seconds and the events are occurring 0.2 seconds later on the even seconds, all in GPST time, just as we set them up to occur and verified with u-center.

event8

So I don’t fully understand why the time stamps are appearing out of sequence with the CSGShop M8T data and not in the Emlid M8T data.  It may be that Emlid has configured the hardware somehow so this can not happen.  If this is true, then there should be no issue using the Emlid RTKLIB code with Emlid data but be careful using it with data from other hardware.  If anybody has any additional insight into this discrepancy please leave a comment.

I should also mention that all these code changes are in the core code so are present in both the command line apps as well as the GUI apps.  The most recent demo5 executables (b29e) do not contain the fix for interpolating delayed events and will function the same as the Emlid code.  The Github respository does have this fix.  The fix will also be in the demo5 b30 executables which I hope to release soon.

New release of demo5 B29e RTKLIB code

With the recent upgrades to the SwiftNav firmware and the upcoming release of the u-blox F9 receiver the last couple months have been an exciting time in the world of low-cost precision GNSS.!  It has kept me very busy, both making necessary updates to the demo5 version of the RTKLIB code and with consulting work related to the new receivers.  Unfortunately, this has meant I haven’t got a blog post out in over two months.

I have, however, just recently released a new version (b29e) of the demo5 RTKLIB code with some fairly significant changes from the previous version.  These changes have been much more of a group effort than my previous releases, so I first want to thank everyone who helped with the new features.

Here’s a list of the most important changes:

1)  U-blox F9 support:  Support for the new dual-frequency u-blox raw binary messages.  The updated code will now run real-time and post-processed solutions for the F9 receiver using all available raw binary observations and navigation messages.

2) Swiftnav F/W 2.0 support:  Support for the new Galileo and Bediou Swiftnav binary messages.  The updated code will now run real-time and post-processed solutions for the Piksi Multi receiver using all available raw binary observations and navigation messages.

3) Galileo E5b frequency support:  Both the u-blox F9 and the Swiftnav receiver are using the E5b frequency for the second Galileo frequency.  It was difficult to set the option for this frequency in the RTKLIB solutions and including it caused the solutions to run quite slowly.  Since the demo5 code is focused on low-cost receivers, and both SwiftNav and u-blox, the two most popular low-cost dual frequency receivers, are both using E5b, I have re-ordered the frequency tables in RTKLIB so that a three frequency solution now includes L1, L2, and E5b.  Previously, you would need to run what was effectively a five frequency solution to include E5b which caused RTKLIB to run noticeably slower.

4)  Event logging and event position logging:  This is a nice feature that has been available in the Emlid version of RTKLIB for a long time.  I have ported the code over from their open-source code base and have extended support to the Swiftnav receivers as well as the u-blox receivers.  Any events recorded by the receivers (e.g. camera triggers) are decoded from the binary messages and added to the rinex files.  Post-processing the rinex files will now generate two position logs.  The first is unchanged from before, with a solution position for every rover time stamp.  The second, only includes positions for the logged events which are interpolated from the time stamp positions.

5) Fix for using time-tag files to emulate real-time RTKNAVI solutions with file inputs:  This is a really useful feature that was broken by changes ported from the official 2.4.3 code quite a while ago, so it is really nice to have it working again.  Thanks to Christophe for figuring this one out and giving me the necessary code fixes!

6) Reduce unnecessary NTRIP connection requests:  RTKLIB was behaving quite badly on both server and client side whenever a receiver was disconnected without shutting down an NTRIP caster connection and was hammering the caster with nearly continuous connection requests.  This was causing bandwidth issues for the NTRIP casters, and was causing some users (including me) to get temporarily banned for misuse.   Thanks to David from SNIP for helping resolve this one and also for helping me to test the code.

7)  Improve cycle-slip handling for non-u-blox receivers:  RTKLIB was ignoring cycle-slips in cases where the carrier-phase was not set or set to zero.  This was causing it in some cases to ignore valid cycle-slips which can significantly degrade the solution.  The u-blox receiver code already had a fix for this so this change primarily affects non-ublox receivers

Several of these changes were written specifically for clients that needed the features or fixes for their own use but were willing to share them with the larger community.  I appreciate their willingness to share and hope I can continue to bring more changes this way into the open-source code in the future.

I’ve had a chance to run real-time and post-processed solutions with this code with raw observations from both the u-blox F9 receivers and with the SwiftNav receivers with F/W 2.0 and am getting great results with both of them.  I hope to share more results in the near future, but just wanted to say that the quality and number of raw observations I am seeing from both receivers is excellent.

If you’d like to try the new code, Windows executables can be downloaded here and the source code is available here.

 

 

 

 

 

 

 

Comparison of the u-blox M8T to the u-blox M8P

I recently acquired a couple of  u-blox C94-M8P receivers and so I am now able to do a direct comparison between the u-blox M8T and M8P modules, something I’ve been wanting to do for a while.

I believe the hardware between the two receivers is identical, the differences are only in firmware.  The most significant difference in firmware is that the M8P includes an internal RTK solution.  In order to squeeze this into the firmware, however, they had to remove support for the Galileo and SBAS constellations, so this is another fairly significant difference.

Cost, of course, is also different.  The M8T receivers I usually use are available from CSGShop for $75.  CSG sells an M8P receiver for $240 or you can buy a kit with two C94-M8P eval boards from u-blox for $400.  The C94-M8P boards also include on-board radios.

In this post, I will describe how I used RTKLIB and a cell phone hot spot to connect the M8Ps rather than using the internal radios.  I will also compare the RTKLIB solutions for a pair of M8T receivers with the internal u-blox RTK solution for a pair of M8P receivers. I hope to compare the RTKLIB solution to the internal solution for a pair of M8Ps in a future post.  If you are mostly interested in the M8T to M8P comparison results, you can jump directly to the end of this post.

To set up the experiment I first connected both a C94-M8P receiver and a CSG M8T receiver to the GPS survey antenna on my roof using a signal splitter.  I then connected both receivers to a laptop with USB cables.  I configured the M8P using u-center following instructions in the C94-M8P Setup Guide with a few modifications.  First of all, I normally use an NTRIP caster over a cell phone hot spot for my real-time data link so didn’t want to bother with the on-board radios.  I disabled the radios following the instructions in the setup guide.  This involves removing a plastic cover, soldering a wire to a capacitor, drilling a hole in the plastic cover to run the wire, then plugging the other end into a pin on the connector.  It is also possible to do this by connecting an external voltage and ground to the correct pins on the connector, but a simple jumper option would have been a lot more convenient.

The setup instructions are intended to run the setup and solution output messages over the USB port while running the RTCM raw observation messages between receivers over the UART interface.  The UART interface is internally connected to the radios.  Since I am not using the radios, I wanted to run all communication over the USB interface to avoid extra cables.  To do this, I disabled the UART interface and configured the USB interface for UBX messages in and RTCM messages out using the UBX-CFG-PRT configure command from u-center.  Following the C94-M8P setup instructions, I then specified a fixed base station location with the UBX-CFG-TMODE3 command and enabled 1005,1077,1087, and 1230 RTCM messages which include the raw observations, base station location, and GLONASS biases.

I setup the base station M8T receiver as I usually do to output the raw observations using the UBX-RXM-RAWX messages.

I then started two copies of the RTKLIB STRSVR app on the base station laptop and streamed both sets of base observations to an NTRIP server as I’ve described in an earlier post using the free RTK2GO.com community NTRIP server.  With this setup, I can receive the NTRIP streams anywhere I can get cell phone coverage, using a cell phone hot spot and a laptop connected to the two rovers and I can test over much longer distances than the radios would allow.

One thing to be aware of is that there are separate versions of the receiver firmware for the M8P base and M8P rover.  I didn’t realize this at first.  It turned out that both of my receivers came loaded with the rover firmware so I spent an embarrassingly long time unsuccessfully trying to configure one of them as a base station.  Once I realized the problem, I was able to fairly quickly download the base firmware from the u-blox website, then use u-center to download the base station firmware to the receiver.

Next, I attached the two rover receivers to a laptop using USB cables and to a single antenna using a signal splitter.  To make the results more comparable to some of my other recent experiments I used the same GPS-500 L1/L2 antenna from SwiftNav that I used for those experiments.  This is a more expensive antenna than generally would be used with these receivers but I wanted to avoid mixing differences between antennas with differences between receivers.

The M8P rover does not need much configuration since it will by default process any incoming RTCM messages as inputs to an RTK solution.  I did configure the USB port  to support NEMA, UBX, and RTCM messages in and UBX and NMEA messages out.  For the static rover test, I left the position message output rate at the default 1 Hz, but increased it to 5 Hz for the dynamic rover test.  I suspect this only affects the message output rate, and not the solution itself since the solution is probably run at a faster internal rate.

The only other setting I modified in the M8P rover receiver was the dynamic model of the navigation mode using the UBX-CFG-NAV5 message.  I set it to “Pedestrian” for my static rover test and “Automotive” for my moving rover test.

I then started another copy of STRSVR on the rover laptop to stream the M8P base station data from the NTRIP server to the M8P rover over the USB COM port.

At this point, getting the solution output messages from the M8P rover is a little tricky.  Only a single user can attach to a Windows COM port at one time and the STRSVR app is not fully bi-directional.  One solution might be to use u-center to stream the NTRIP data and receive the rover messages but I did not verify if this is possible.

Instead, I used a feature of STRSVR that allows you to pipe the data coming from the other direction to a TCP/IP port which can then be processed by either another copy of STRSVR, or plotted with RTKPLOT, or used as an input to RTKNAVI, or all three at once.  Below, on the left, I show how I modified the STRSVR setup that streams the base data from the NTRIP client to the rover by checking the “Output Received Stream to TCP Port” and selecting port 1000.  On the right, I show the STRSVR setup necessary to stream this incoming data from the rover to a file.  This is a convenient work-around for the problem of only being able to connect one user at a time to a COM port.

strsvr2

In my case I configured the rover receiver to send both the M8P internal solution position using NMEA messages and the raw observations using UBX messages so that I could post-process the raw observations later with RTKLIB.  In general though, it is only necessary to send the NMEA messages.  I configured the rover to send GGA and RMC NMEA messages, but others will work as well.

For the M8Ts, I ran a real-time RTKLIB solution using RTKNAVI and my normal kinematic solution configuration for both static and moving rover tests.  As usual, I used the demo5 version of RTKLIB for this test.

So, how did they compare?  First of all, a few differences to consider between the solutions.   The M8P solution only uses GPS and GLONASS satellites since the SBAS and Galileo satellites have been disabled in the M8P firmware as I mentioned earlier.  This should give the M8T solution an advantage.  The M8P also has limited processing power relative to the laptop running the RTKLIB solution, so this may also give the M8T solution an advantage.  On the other hand, I’m sure that u-blox has lots of smart people that know all the internal details of the hardware which should give the M8P solution an advantage.

For my first comparison, I did a a static rover test with the antenna located on a tripod a few meters from the house and partially obstructed by trees.  To avoid different starting conditions between the two receivers, I connected both receivers to the antenna and waited till they both converged to fixed solutions before starting the test.  I then disconnected the antenna for about 30 seconds, and then reconnected it.  This will cause both receivers to lose lock with all satellites and the solutions will have to re-converge from scratch so this should be a fair comparison.  I disconnected and reconnected the antenna several times to compare the times to re-acquire fix and the accuracies of the fixes.

The results are plotted below, the M8P internal solution on the top, and the real-time RTKLIB M8T solution on the bottom.  I re-connected the antenna five times.  Once, the internal M8P solution re-acquired fix slightly quicker than the RTKLIB M8T solution, once the M8T re-acquired fix slightly quicker than the M8P.  The other three times, the M8T re-acquired fix significantly quicker than the M8P.   The M8P times to re-acquire varied from 52 to 220 seconds.  The M8T took from 50 to 76 seconds.

The M8T RTKLIB solutions had no false fixes, the M8P internal solutions had false fixes with several meter errors for over five seconds in two of the five tests.  The false fixes are circled with red in the plot below.

m8p1

The E-W and N-S axes matched within one centimeter between the two solutions.  The U-D axis at first appears to differ by 21.5 meters between the two solutions but this is because I specified the RTKLIB vertical solution to be relative to the ellipsoid, while the M8P solution is relative to the geoid.  If I subtract the geoid to ellipsoid offset (available in the GGA message from the M8P), then the two solutions match in the vertical axis as well.

Overall, I would have to say that in this particular run,  the RTKLIB M8T solution out-performed the M8P internal solution by a fairly significant amount.

One other observation about the M8P solution is that the precision reported (at least in the GGA message) is only to one centimeter in the horizontal axes and 10 cm in the vertical accuracy.  I didn’t see any obvious way to get outputs with better precision than this, at least with the NMEA messages.  [Note 8/16/18: It turns out that the UBX-CFG-NMEA message can be used to enable high precision mode to fix this.  Thanks to Charles Wang for pointing this out in a comment]

Next I mounted the same antenna on the roof of my car and drove around the neighborhood.  The sky view varied from nearly unobstructed to moderate tree canopy.  Here are the results of that test, the MP internal RTK solution on the left, and the M8T real-time RTKLIB solution on the right.

m8p2

The fix rate for the M8P solution was 52.4%.  The M8T solution was noticeably better with a 95.2% fix rate.

Here’s a plot of the difference between the two solutions (green indicates both solution are fixed, yellow indicates that at least one is float).  The U-D axis differences are fairly large, mostly because of the 10 cm vertical precision of the M8P position messages.  There is also a fairly large discrepancy between the two solutions around 22:55:00.  This corresponds to a 15 second gap in base station data, probably due to a loss of cell phone reception.  This seems to be a large error for such a short base outage but I was not able to narrow down the cause beyond this or determine which receiver contributed more to this combined error.  This probably deserves more investigation in a future post.

m8p2d

Again, the real-time RTKLIB M8T solution appeared in this test to be better than the internal M8P solution.

The most likely reason the M8T is getting a better solution is that it is using more satellites.  Here are the rover raw observations for the M8P on the left, and the M8T on the right.  With the GPS and GLONASS constellations, both receivers are seeing 13 satellites.  With Galileo and SBAS, the M8T is seeing an additional 7 satellites.  One of these Galileo satellites is not fully operational yet and so is not used in the solution, but that still gives 6 extra satellites, nearly 50% more than the M8P solution.

m8p3

If the extra satellites are what is improving the M8T solution, then running a solution with the M8T data without the SBAS and Galileo satellites should give a solution similar to the M8P solution.

This is easy to do, so let’s try it.  Here’s a post-processed solution for the M8T data using only the GPS and GLONASS satellites.

m8p4

Fix rate is 66.5%, reasonably close to the 52.4% fix rate from the M8P internal solution.  This suggests that a large part of the improvement for the M8T solution is coming from the additional satellites and not from any differences in the solution algorithms.

As in all my comparisons, this is intended to be one user’s initial experience, and not any kind of rigorous comparison test.  Please interpret these results with that in mind.  If you have experiences that differ from these I would be very interested to hear about them.

Glonass Ambiguity Resolution with RTKLIB Revisited

To get a high precision fixed solution in RTKLIB we need to resolve the integer ambiguities that come from the carrier phase measurements.  Resolving the integer ambiguities for the GLONASS satellites is more challenging than resolving them for the other constellations.  This is because, unlike the other constellations, the GLONASS satellites all transmit on slightly different frequencies.  This introduces an additional bias error in the receiver hardware.

These hardware biases are constant, generally the same for all receivers from the same manufacturer, are proportional to carrier frequency and are similar between L1 and L2.

In the demo5 version of RTKLIB, there are four choices for how to handle GLONASS ambiguity resolution (AR). I will cover all four briefly, but then focus on the “autocal” setting which I have enhanced in the most recent version (b29c) of the demo5 code.

Off:  If Glonass  AR is set to “Off”, then the raw measurements from the Glonass satellites will be used for the float solution but ambiguity resolution will be done only with satellites from the other constellations.  If you are not using the demo5 version of RTKLIB, this is usually your only choice when using receivers from different manufacturers for the rover and the base.  However, you are giving up a significant amount of information by ignoring the GLONASS ambiguities and so I would not recommend this setting if you are using the demo5 code, unless of course your receivers don’t support the Glonass satellites.

On:  If Glonass AR is set to “On” then RTKLIB will treat the Glonass ambiguities the same as the ambiguities from the other constellations and will not make any attempt to account for the additional hardware biases.  Use this setting if your base and rover receivers are from the same manufacturer, since in this case, the biases will cancel and can be ignored.  There are also some cases in which different manufacturers have equal or nearly equal biases as we will see later, in which case you can also use this setting.  This is your best solution for dealing with Glonass ambiguities.  I always try to use matched receivers for base and rover if possible.

Fix-and-Hold: This is an option I have added to the demo5 code for Glonass AR.  It is an extension to the “fix-and-hold” method used for other constellations but instead of using the additional feedback to track the ambiguities, it uses it to null out the hardware biases.  I recommend this setting when using the demo5 code with unmatched receivers.  It takes advantage of the additional information in the Glonass ambiguites most of the time.  However, fix-and-hold is not enabled until after a first fix has been achieved, and so the Glonass ambiguities are not available until then.  This can mean longer time to first fix and less robustness compared to the “On” option, so don’t use this option for matched receivers.

Auto-cal:  This option adds additional states to the kalman filter to estimate the receiver hardware biases as a function of carrier frequency, one state for L1, another for L2.  In previous experiments I had not had any success with it.  Recently, however, I discovered that if I adjusted the filter settings, it can be effective for a zero baseline case, where base and rover are both connected to the same antenna so that almost all other errors are completely cancelled.  With a little more experimentation I also found that for short baselines it can also be effective if the kalman filter state is pre-set to something close to the final value before the solution is started.  It will then usually converge to the correct bias value.  However, there is currently no mechanism in the code to adjust any of these values, so I have not found this mode to be useful in its current implementation.

To make the auto-cal option more flexible, and hopefully more useful, I made a few modifications to it in the b29c code.  I added the capability to pre-set the initial state value and also to adjust the internal filter settings, specifically the initial variance and process noise for this state.  The units for the state, and hence for the initial value are in meters per frequency channel and values generally are within +/-5 cm per channel.  I used some existing config parameters that are currently unused to reduce the amount of code I needed to change.  Unfortunately it means that the names are not as descriptive as they could be.  The new config parameters are:

pos2-arthres2 = relative GLONASS hardware bias in meters per frequency slot
pos2-arthres3 = initial variance of GLONASS hardware bias states
pos-arthres4 = process noise for GLONASS hardware bias states

Bias values have been published for some of the most popular geodetic quality receivers but are generally not available for lower-cost or less popular receivers.  Here is a table of values from a paper published by Lambert Wanninger in 2011 for nine receiver manufacturers.

biases

I was able to verify these results for Trimble, Leica, and Novatel, but I found a much lower value for Septentrio so I suspect the biases may have changed in their newer receivers.

To demonstrate the modified autocal option, I will start with a zero baseline case between a ComNav receiver and a Tersus receiver.  It is easiest to measure the hardware biases in the zero baseline case because most other errors will cancel and the hardware biases will be the dominant error.  In this case, I have significantly reduced the initial variance setting from the original value of 1.0 to 1E-7 and increased the process noise from 1E-6 to 1E-3.

I have run the solution several times with the initial bias value set to different numbers between -.05 and 0.06.  Here are the results for both L1 and L2.

biases1

The convergence occurs just after first fix is achieved.  If a fix is not achieved, then the state will not converge as you can see above for the 0.06 example.   In this case, the initial value was too far from the correct value and prevented getting a fix.  As you can see, all the other cases converged towards a single value around -.022, both for L1 and for L2.

Another way to visualize the error in the initial value is to look at the GLONASS residuals after first fix is achieved.  The plot below shows the GLONASS L1 carrier phase residuals  for different initial values, for 0.03 on the left, -0.05 in the middle, and what I believe is the correct value for this receiver combination of -.022 on the right.

acal1

Here are the same plots for the L2 carrier phase residuals.

acal2

Through a slightly tedious process, I am fairly easily able to iterate the residuals down to near zero for different pairs of receivers in my possession.  Note that this gives me the relative difference in biases for each receiver pair, and not absolute values for each receiver, unlike Wanniger’s table which is for absolute biases.

Extending the table to receivers used in nearby CORS stations is a little more challenging because the initial bias value needs to be fairly close to get a first fix and hence a convergence, but still possible if the base station is not too distant.   I found data sets that included CORS data from Leica, Novatel, Trimble, and Septentrio receivers.  Using the above procedure to iterate the residuals down to near zero, I was then able to extend my table and make the values absolute by choosing the unknown offset to make my bias pairs align with Wanninger’s table.  This is the resulting table I created.

[Note: table updated 3/16/20:]

ComNav               =   2.3 cm
Leica                      =   2.3 cm
Novatel                 =  2.3 cm
Septentrio           = -0.3 cm
Spectra Physics =  0.0 cm
SwiftNav              =  0.0 cm
Tersus                   =  0.0 cm
Topcon                 =  0.0 cm
Trimble                = -0.7 cm
u-blox M8T        = -3.2 cm
u-blox F9P          =  0.0 cm

To generate an initial value for the bias state from this table for an RTKLIB solution, subtract the base station bias from the rover bias, then divide by 100 to convert from centimeters to meters.  This value can then be used to set the “pos2-arthres2” config parameter in the config file.  For the RTKPOST and RTKNAVI GUI option menus I have labeled this “Glo HW Bias”.

To test this code on an independent set of data after generating the table, I used a data set recently sent to me by a reader.  It consists of a u-blox  M8T receiver for rover and Leica receiver just a few kilometers away for base, and was collected in Europe.  The rover position was static but I ran the solution in kinematic mode to make the solution a little more challenging and to make any errors in the solution more visible.

To generate the correct config value for RTKLIB I  subtracted the Leica bias of 2.3 cm from the above table from the u-blox bias of -3.2 cm to get a relative bias between receivers of -5.5 cm or -0.055 m.  I added “pos2-arthres2=-0.055” to the config file and then ran the solution four times, with pos2-gloarmode set to “off”,”fix-and-hold”,”autocal”, and “on”.  Although I left the bias value set for all runs it is ignored unless gloarmode is set to autocal.

Here are the times to first fix, the number of satellite pairs used for the initial fix, and the number of satellite pairs being used for fix after 10 minutes.

  Time to # sat pairs used # sat pairs used for
GLO AR mode first fix for initial fix fix after 10 min
OFF 4:10 7 7
Fix&Hold 4:10 7 11
Autocal 1:05 14 14
On 6:47 14 14

As you would expect, the time to first fix for gloarmode=”off” was the same as “fix-and-hold” since “fix-and-hold” does not use the GLONASS satellites for initial fix.  After 10 minutes it was still only including four of the GLONASS satellites in the ambiguity resolution which was a little unusual, typically I would have expected more GLONASS satellites to be included.

With gloarmode=”autocal”, the time to first fix was reduced from 250 seconds to 65 seconds and the number of satellites included in the first fix increased from 7 to 14., both significant improvements.

The most surprising thing in this data is that when gloarmode was set to “on” it acquired a fix at all.  In many similar cases it will never get a fix.  The GLONASS carrier phase residuals after initial fix were very high though as can be seen below.  The left plot is with gloarmode set to “on”, and the right plot is with it set to “autocal”.

biases3

The ambiguity resolution ratio was also much higher when autocal was enabled as can be seen below (yellow/green=autocal, olive/blue=on) which improves robustness.

biases2

The large residuals did not affect the solution position, as the two solution did not differ by more than 2 mm at any time.  The autocal solution however is much more robust in the sense that it is less likely to lose fix.

Although I have found the results with autocal enabled are generally excellent with relatively short baselines (<10 km), I have found the results less encouraging for longer baselines (>25 km).  In these case I have found that I often get better results with pos-gloarmode set to “fix-and-hold” then I do with “autocal”.  I don’t understand exactly why this is, but suspect that the fix-and-hold correction is more general and may be correcting for more than just the GLONASS hardware biases.

The code changes for this feature are included both in my Github repository and in the newest (demo5 b29c) executables available to download from the rtkexplorer website.   If you choose to experiment with this feature, please let me know if you find any errors in my table, or can add values for any additional receivers.

[Note 6/17/18:  I had a issue with uploading the executables to the website.   If you downloaded them prior to 6/17/18, please download again to get the updated version.] 

PPP solutions with SSR corrections for a single frequency receiver

In my last post, I demonstrated some PPP solutions using real-time SSR corrections from the CLK93 data stream with various dual frequency receivers.  Results were quite good with errors after four hours generally below six centimeters in each axis.

Many of my experiments are done using RTK solutions with short baselines where the differences between dual frequency receivers and single frequency receivers can be fairly small.  With PPP solutions however there are significant differences between single frequency and dual frequency receivers.  This is because the ionospheric errors increase with increasing baseline and the dual frequency measurements are much more effective at coping with these errors.

To demonstrate this, I duplicated the previous experiment with a single frequency receiver, collecting twelve hours of raw observations with a u-blox M8T receiver along with the CLK93 real-time data stream for SSR corrections.   I processed the data with the same configuration settings as last time, except using “L1” instead of “L1+L2” for frequencies and ionospheric corrections set to  “broadcast” instead of “ionospheric-free” (dual-freq) corrections.

As expected, the errors, even after 12 hours were fairly large.  Here is the result.   Even after 12 hours, the vertical error was nearly two meters.

ssr4

Presumably the single frequency PPP/SSR results will improve if RTKLIB is extended to support the RTCM SSR Phase 2 and Phase 3 ionospheric correction messages.

Swiftnav experiment: Improvements to the SNR

In my previous couple of posts, I evaluated the performance of a pair of dual freqeuncy SwiftNav Piksi multi receivers in a moving rover with local base scenario.  I used a pair of single frequency u-blox M8T receivers fed with the same antenna signals as a baseline reference.

It was pointed out to me that the signal to noise ratio (SNR) measurements of the rovers were noticeably lower than the bases, especially the L2 measurements and that this might be affecting the validity of the comparison.  This seemed to be a valid concern so I spent some time digging into this discrepancy and did indeed find some issues.  I will describe the issues as well as the process of tracking them down since I think it could be a useful exercise for any RTK/PPK user to potentially improve their signal quality.

Previously , in another post, I described a somewhat similar exercise tracking down some signal quality issues caused by EMI from the motor controllers on a drone.  In that case, though, the degradation was more severe and I was able to track it down by monitoring cycle slips.  In this case, the degradation is more subtle and does not directly show up in the cycle slips.

Every raw observation from the receiver generally includes a signal strength measurement as well as pseudorange and carrier phase measurements.  The SwiftNav and u-blox receivers both actually report carrier to noise density ratio (C/NO), rather than signal to noise ratio (SNR) but both are measures of signal strength.  They are labelled as SNR in the RTKLIB output, so to avoid confusion I will refer to them as SNR as well.  I will only be using them to compare relative values so the difference isn’t important for this exercise, but for anyone interested, there is a good explanation of the difference between them here.  Both are logarithmic values measured in dB or dB-Hz so 6 dB represents a factor of two in signal strength.

Since the base and rover have very similar configurations we would expect similar SNR numbers between the two, at least when the rover antenna is not obstructed by trees or other objects.  I selected an interval of a few minutes when the rover was on the open highway and plotted SNR by receiver and frequency for base and rover.  Here are the results, base on the left and rover on the right.  The Swift L1 is on the top, L2 in the middle, and the u-blox L1 on the bottom.  To avoid too much clutter on the plots, I show only the GLONASS SNR values, but the other constellations look similar.

snr1

Notice that the L1 SNR for both rovers is at least 6 dB (a factor of 2) lower than the base, and the Swift L2 SNR is more like 10 dB lower.  These are significant enough losses in the rover to possibly affect the quality of the measurement.

The next step was to try and isolate where the losses were coming from.  I set up the receiver configurations as before and used the “Obs Data” selection in the “RTK Monitor” window in RTKNAVI to monitor the SNR values in real time for both base and rover as well as the C/NO tracking window in the Swift console app.  I then started changing the configuration to see if the SNR values changed.  The base and rover antennas were similar but not identical so I first swapped out the rover antenna but this did not make a difference.  I then moved the rover antenna off of the car roof and onto a nearby tripod to see if the large ground plane (car roof) was affecting the antenna but this also did not make a difference.  I then removed the antenna splitter, but again no change.

Next, I started modifying the cable configuration between the receivers and my laptop.  To conveniently be able to both collect solution data and be able to collect and run a real-time solution on the raw Swift observations, I have been connecting both a USB serial cable and an ethernet cable between the Swift board and my laptop.  My laptop is an ultra-slim model and uses an etherent->USB adapter cable to avoid the need for a high profile ethernet connector.  So, with two receivers and my wireless mouse, I end up having more USB cables than USB ports on my computer and had to plug some into a USB hub that was then plugged into my laptop.

The first change in SNR occured when I unplugged the ethernet cable from the laptop and plugged it into the USB hub.  This didn’t affect the L1 measurements much but caused the Swift L2 SNR to drop another 10 dB!  Wrong direction, but at least I had a clue here.

By moving all of the data streams between Swift receiver and laptop (base data to Swift, raw data to laptop, internal solution to laptop) over to the ethernet connection I was able to eliminate one USB serial port cable.  This was enough to eliminate the USB hub entirely and plug both the USB serial cable from the u-blox receiver and the ethernet->USB cable from the Swift receiver directly into the laptop.  I also plugged the two cables into opposite sides of the laptop and wrapped the ethernet->USB adapter with aluminum foil which may have improved things slightly more.

Here is the same plot as above after the changes to the cabling from a drive around the neighborhood.

snr2

I wasn’t able to eliminate the differences entirely, but the results are much closer now.  The biggest difference now between the base configuration and the rover configuration is that I am using a USB serial cable for the base, and a ethernet->USB adapter cable for the rover so I suspect that cable is still generating some interference and that is causing the remaining signal loss in the rover.  Unfortunately I can not run all three streams I need for this experiment over the serial cable, so I am not able to get rid of the ethernet cable.

I did two driving tests with the new configuration, similar to the ones I described in the previous posts.   One was through the city of Boulder and again included going underneath underpasses and a parking garage.  The second run was through the older and more challenging residential neighborhood.  Both runs looked pretty good, a little better than the previous runs but it is not really fair to compare run to run since the satellite geometry and atmospheric conditions will be different between runs.  The relative solutions between Swift and u-blox didn’t change much though, which is probably expected since the cable changes improved both rovers by fairly similar amounts.

Here’s a quick summary of the fix rates for the two runs.  The fix rates for the residential neighborhood look a little low relative to last time but in this run I only included the most difficult neighborhood so it was a more challenging run than last time.

Fix rates

City/highway Residential
Swift internal RTK 93.60% 67.50%
Swift RTKLIB PPK 93.70% 87.90%
U-blox RTKLIB RTK 95.70% 92.80%
U-blox RTKLIB PPK 96.10% 91.10%

Here are the city/highway runs,  real-time on the top, post-process on the bottom with Swift on the left and u-blox on the right.  For the most part all solutions had near 100% fix except when recovering from going underneath the overpasses and parking garage.

snr4

Here are the same sequence of solutions for the older residential neighborhood.  This was more challenging than the city driving because of the overhanging trees and caused some amount of loss of fix in all solutions.

snr5

Here’s the same images of the recovery after driving under an underpass and underneath a parking garage that I showed in the previous post.  Again, the relative differences between Swift and u-blox didn’t change much, although the Swift may have improved a little.

snr1

Overall, the improvements from better SNR were incremental rather than dramatic, but still important for maximizing the robustness of the solutions.  This exercise of comparing base SNR to rover SNR and tracking down any discrepancies could be a useful exercise for anyone trying to improve their RTK or PPK results.