GPS for Yaw (aka Moving Baseline)

Two UBlox F9 GPS modules can be used to estimate yaw which removes the need for a compass which may suffer from magnetic interference from the ground or the vehicle’s motors and ESCs. This works even if the GPSs do not have RTK fix (RTCM data from a fixed RTK station or NTRIP server).

Also, recently, single unit GPSes which utilize Internal Moving Baseline (see below) are becoming available, like the Blicube RTK GPS.

GPSes from ArduPilot Partners that are known to work are shown on the GPS/Compass (landing page)

Note

Ublox F9P modules must run firmware version 1.13 or higher and constellations configured. See U-Blox F9P Firmware Update.

Hardware Setup

  • Two Ublox F9 GPSs should be placed on the vehicle at least 30cm apart (horizontally)

  • The 1st GPS and 2nd GPS should be connected to a serial/telem ports on the autopilot. These instructions assume Serial3 and Serial4 are used but any serial ports should work as long as the first port using protocol 5 is connected to one of the GPS.

  • Serial GPS modules must be connected to ArduPilot via their UART1 connectors, DroneCAN modules via CAN (if the DroneCAN modules support Moving Baseline), or interconnected per their manufacturer instructions.

Configuration

Serial GPS

DroneCAN GPS

If DroneCAN GPS are used, then configure the CAN/DroneCAN ports as explained in DroneCAN Setup and instead of setting up the SERIAL port protocols above, make sure that no SERIAL ports are setup with GPS protocol (“5”). Also be sure that the two DroneCAN GPS are on the same physical CAN bus from the autopilot. This usually requires that a CAN bus splitter be used. Then set these parameters:

For either Serial or DroneCAN GPS also set:

The above configurations assumes that you want the RTCMv3 data between the two GPS modules to go via the flight controller board.

Note

You may instead install a cross-over UART cable between the two UART2 connectors on the two GPS modules (Assuming they are serial rather than DroneCAN). If you do that then you can set GPS_DRV_OPTIONS = 1 which tells the u-blox GPS driver to configure the two GPS modules to send RTCMv2 data over UART2. On DroneCAN modules, a second CAN port is provided to allow this direct connection for RTCMv2 data. In that case, set GPS_DRV_OPTIONS = 8.

Note

should be possible to mix and match a Serial GPS and a DroneCAN GPS, but this configuration has not been tested as yet.

Note

Do not use GPS_AUTO_SWITCH = 2 (Blend) when using Moving Baseline configurations.

Internal Moving Baseline Systems

Some vehicle GPS provide GPS for Yaw utilizing a completely internal dual gps unit and managing the inter gps communication totally internally, rather than having ArduPilot pass data between the GPSes. An example of this system is the Blicube GRTK.

This only requires that the GPS be attached to a SERIALx port using SERIALx_PROTOCOL = 5 (GPS)

and setting only:

  • GPS_TYPE = 5 (NMEA)

  • EK3_SRC1_YAW = 2 (“GPS”) or 3 (“GPS with Compass Fallback”) if a compass(es) is also in the system.

Testing

In a location with good GPS reception point the vehicle at a landmark some distance away and then check the heading on the ground station matches. Rotate the vehicle and ensure the heading on the ground station updates correctly.

If the heading is reversed, then the GPS_POS_xxx parameters have probably been set incorrectly.

Note that it can take some time for the two GPS modules to get a sufficiently good fix for yaw to work. The ArduPilot GPS driver validates that the fix is good enough in several ways:

  • that the rover GPS module is in fix type 6 (fixed RTK)

  • that the reported distance between the two modules matches the distance given by the GPS position parameters within 20%

  • that the reported heights of the two GPS modules match the attitude of the vehicles is within 20% of the distance between the two GPS modules

Video Demo

Using Moving Baseline Yaw to Reject Magnetic Disturbances