Do-It-Yourself realtime DGPS

dgps     

The earth ionosphere leads to reflections of the satellite signal, and that changes (increases) the time-of-flight (ToF) of the signal leading to error-prone distances (wrong measurements) at the GPS receiver.
The solution to this problem is relative measurement (differential GPS): measuring time-of-flight at a 1st near-by static GPS receiver (the ‘station’) and then using the time difference of the 2nd GPS receiver (the ‘rover’) measured time-of-flight to compute the relative distance to the static receiver (see above triangle).

dgps_top

Requires:

  • 2x RAW output capable GPS receivers
    example:

    • SkyTraq NS-HP (S2525F8-RTK,  update rate 1 Hz, can even run RTK without RTKLIB software simply by sending GPS receiver 1 RAW output to GPS receiver 2 RAW input! – around 50 EUR)
      dgps     ns_hp_rtk  ns_hp_xbee_pro  zigbee_pro
    • SkyTraq 1315F RAW (update rate 20 Hz –  eval kit around 100 EUR)
    • UBlox LEA4T (update rate 10 Hz –  ready module around 30 EUR)
  • 2x active GPS antennas (example: Tallysman TW2710, TW3440, Sokkia GSR1700 CSX, Trimble Bullet III 3.3V – on the roof, a simple patch antenna can work as well)
  • Wireless infrastructure (Wifi, XBee, Zigbee, GSM, …)
  • RTKLIB

raw_gps

GPS signal:

  • ordinary GPS receivers use C/A code to measure position – a C/A code chip is roughly 300 meters
  • RAW receivers can count carrier cycles – each carrier cycle has a wave length of 19cm

The RAW GPS signal contains for each ranging measurement:

  • Pseudo random noise code number (PRN code)
  • Distance in meters (aka pseudorange)
  • Accumulated carrier (number of L1 cycles)   [ signal phase? ]
  • Doppler frequency (Hz)

1. Find the base station position (Lat/Lon/Height)
Measure position for 12-24 hours and write down the final position – RTKNAVI options:

  • Input streams:
    Rover: Choose port and baud rate
    Station: none
  • Settings 1:
    Positioning Mode: PPPstatic
    rtklib_ppp

2. Compute precise rover position using realtime DGPS
RTKNAVI options:

  • Input streams (both Rover and Base Station):
    Serial: Choose port and baud rate
    Cmd: Choose load -> rtklib_2.4.2/data/skytraq_raw_20hz.cmd   (file will set SkyTraq receiver to 20 Hz)
  • Settings 1:
    Positioning Mode: Kinematic
    Elevation Mask / SNR Mask: 35
  • Settings 2:
    Min Ratio to Fix Ambiguity: 1.0
  • Positions:
    Base Station: Enter your base station position (Lat/Lon/Height)

Checklist for good results:

  • always check RTKLIB ‘Error/Warning’ window
  • SNR should be around 50
  • antennas should have a ground plate (70cm x 70cm)
  • test using sky view (no buildings)

Screenshots:

static 10 minutes test (‘rover’ GPS not moving)
rtklib

3. Garden test (‘rover’ moving in a 20cm rectangle pattern)

Patched RTKLIB
dgps_session

dgps_screenshot

4. Set-up your own RTCM base station
Some low-cost receivers (e.g. ublox 4/5/6/7/8) support DGPS input (RTCM protocol). Can you use RTKLIB to setup your own RTCM base station? Please let me know…

5. Set-up low-cost GPS receiver to receive DGPS signal (RTCM protocol)
Some low-cost receivers (e.g. ublox 4/5/6/7/8) support DGPS input (RTCM protocol). ublox receivers support RTCM 2.3 (message types 1,2,3,9).
This allows you to send DGPS signal to your low-cost GPS receiver:
5.1 Install ‘Serial Splitter’ (Eltima) to split 1x COM port into 2x COM ports
5.2 Run ‘STRSVR.exe‘ (RTKLIB) and choose:

  • Input: NTRIP Client (enter server, port, mountpoint, user-id, password)
  • Output: Choose 1st serial port (and baud)
    Optionally: Activate convertersion (RTCM protocol version)
    Press ‘Start’. Now your GPS-receiver will receive DGPS data.

5.3 Run ublox u-Center and connect to your GPS receiver via 2nd serial port:

  • Now your GPS receiver should output DGPS data:

comsplit

Further information

RTCM message examples (typical NTRIP messages and what messages typical receivers understand):

Bochum (RTCM2) sends: 1,18,19
[1]: corrections without phase
18: phases observations
19: distance observations

and ublox6 understands (RTCM2): 1,2,3,9
[1]: corrections without phase
2: delta-corrections without phase
3: reference station parameters
9: corrections without phase (partial)
—-

Dresden/Helgoland (RTCM3) sends: 1004,1006,1008,1012,1033
[1004]: observations incl. phase and SNR (L1+L2)
[1006]: reference station position and height
1008: antenna type
1012: GLONASS observations incl. phase and SNR
1033: antenna type

and Skytraq S2525F8-RT understands (RTCM3):
1002: observations incl. phase (only L1)
[1004]: observations incl. phase and SNR (L1+L2)
1005: reference station position
[1006]: reference station position and height

9 thoughts on “Do-It-Yourself realtime DGPS”

  1. Mr. Grau,

    I am thinking to reproduce your test for this DGPS with minimum cost and apply the localization to the robot mower. I still think probably this is the better way than others such as you tested: LiDAR, Radio frequecy beacons, outdoor slam etc.

    Is the antenna on your roof “a simple patch antenna” in your pictures?

    I am located in the US, will the same RAW output capable GPS receivers (I am thinking to get the SkyTraq NS-HP too) ?

    What would be your most preferable way to remove the Perimeter Wire? DGPS, LiDAR, Radio Frequency beacons or outdoor slam by RGB-D cameras?

    Thanks
    Jack

    1. Hello Jack,

      DGPS: Yes, I’m using simple patch antennas. I have tested it on the ground (with trees, buildings etc.), and unfortuneately, I cannot get a fix (solution) on the ground. The problem is reflections from trees and buildings. A single frequency GPS will probably only work without any trees, building etc. in the surroundings.

      Perimeter: I think it’s still the way to go. 2D Lidar doesn’t work reliable in 3D (3D Lidar is too expensive), Radio beacons only work again without any obstacles (I have tested Decawave DW1000 outdoor). RGB-D may work (outdoor maybe for some cm distance), but requires a lot of cpu power.

      In the project ‘http://www.ardumower‘ we are using perimeter and can now localize the robot’s position on the ground (using odometry, compass, gyro and a particle filter).

      Regards,
      Alexander

      1. Hello Mr. Grau,

        Thanks for you quick reply and insights. Also thanks for the arduemower team to bring such a good project to everybody. I think the technologies are there (some need more research) however we need to find a cost effective way to apply them on house-hold level robots. Are you or any members of the ardumower team planning to do any further research and test on GPS (multi-frequecy?), 3D LiDAR & RDB-D with a more powerful CPU in future? I think these are still very interesting directions for future R&D efforts.

        I was trying to find the topic on the website about “using perimeter and can now localize the robot’s position on the ground (using odometry, compass, gyro and a particle filter).” Could you advise the link about it?

        Thanks
        Jack

          1. I would be up for doing some trials using differential GPS. I have about 3 robotic mowers and find a perimeter wire too limiting. [ Lack of flexibility of placement of children’s play equipment] and difficultly reaching remote field via narrow track, that has no power or services.

            I’m looking at using the reach modules which may be accurate to 5cm in open skies.

            https://emlid.com/reach/

            I live in a windmill and will be able to place the basestation on the roof. Will be interesting to find out how accurate things are if the rover is close to the house. I suspect I will need a mix of sensors to fully do away with the perimeter wire.

            Initially I would like to get a basic inaccurate (3m) gps solution working and try in a largish field. Is there any basic code available for this purpose on Arduino, so I don’t start reinventing the wheel. Rather build on the Ardumower project and feedback. Anyone thinking of doing something similar, please get in touch – more fun working together!

            Many thanks
            Clive

  2. Hi Clive,
    I’m starting a project that’s similar to an Ardumower. I also decided to get started with the u-blox NEO-6M, to see how accurate I could get with the least expensive GPS option.
    But I think that the u-blox NEO-M8P Base and Rover configuration like the Reach is where I need to be to get real cm level accurate. But the Reach or Drotek Tiny RTK are not cheap and I would like to have a number of rover units. The NEO-7P seems to offer a level of accuracy greater than 2.5m (~<1m) with SBAS + PPP at slower speeds and measurement durations, but also supports DGPS.
    These chip sets have not been out very long, but it seems like there should be more products that offer the RTK abilities the NEO-M8P has to offer. I might wait to see what else comes out for drone aircraft applications before trying to create my owe. I wish there was a NEO-M8P unit with a LoRa RFM69HCW chip, instead of bluetooth or Wifi.
    Robi

  3. Could you comment on how two (or more) GPS RAW receivers could be utilized on a platform (no external base station) are used to compute absolute platform orientation without the need for magnetic compass, etc.? I’m aware that commercial solutions exist for this (so called “satellite compass” or “GPS compass”), but I’d be interested in looking at low-cost DYI implementations, if that’s feasible.

    1. The idea is to measure the time difference of the received signal between two (2D case) or three (3D case) antennas:

      http://www.cactusnav.com/images/satcomp.jpg
      (Source: http://www.cactusnav.com/newsdesk_info.php?newsPath=17&newsdesk_id=16)

      The RAW receivers send phase, signal data, and clock – so in principle it’s possible assuming that you get the clock’s synchronized (either in hardware or in software). I have not seen any DIY attempt though. Even if you get it working with DIY hardware, it will only work without signal reflections, so you will need a good sky view without any obstacles in the near and far range at the height of the antennas.

      What is your intended usage, why not using a magnetic compass? 🙂

      1. The intended usage is accurately measuring winds from the combination of aircraft heading and airspeed and GPS ground velocity. The story I hear from those who do this for a living is that mag compasses aren’t precise enough. I have seen implementations of a dual GPS system that gets the aircraft orientation more accurately and reliably from the phase difference of the arriving GPS signal. But I don’t know exactly how it’s done and whether it could be implemented with off-the-shelf components without buying a commercial (expensive) satellite compass.

Leave a Reply

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

IMPORTANT! To be able to proceed, please enter the magic word 'agedna' so we know hat you are a human)

Enter the magic word:
Please leave these two fields as-is:

A blog on projects with robotics, computer vision, 3D printing, microcontrollers, car diagnostics, localization & mapping, digital filters, LiDAR and more