GPS for Yaw (aka Moving Baseline)

New RTK GPS modules, such as a pair of Ublox F9’s, devices based on the Unicore UM-982 or some dual-antenna devices can be used to estimate yaw, in addition to providing position information. This 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 an RTK fix (RTCM data from a fixed RTK station or NTRIP server).

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.3.2 or higher and constellations configured. See U-Blox F9P Firmware Update.

Hardware Setup

GPS Yaw estimation relies on the detection of signal delays from each satellite as they reach two separated antennas. The GPS system may consist of dual or a single module, but two antennas are required in each case.

  • The antennas must be separated by at least 30cm on the vehicle.

  • For dual unit systems, the 1st GPS and 2nd GPS should be connected to the serial/telem ports on the autopilot or via DroneCAN. The following parameter instructions assume Serial3 and Serial4 are used for serial connecting GPSes but any serial port(s) should work as long as the first port using protocol 5 is connected to one of the GPS.

  • Dual unit Serial GPS modules must be connected to ArduPilot via their (not the autopilots’s) UART1 connectors, DroneCAN modules via CAN , or interconnected per their manufacturer instructions.

Configuration

Note

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

Common Parameter Setup

  • AHRS_EKF_TYPE = 3 (to use EKF3)

  • EK2_ENABLE = 0 (to disable EKF2)

  • EK3_ENABLE = 1 (to enable EKF3)

  • EK3_MAG_CAL is not used for this feature so it can be left at its default value (“0” for Plane, “3” for Copter, “2” for Rover)

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

Note

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

Dual Serial F9P GPS

Dual DroneCAN F9P 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:

The above dual unit configurations assumes that you want the RTCMv3 data between the two GPS modules to go via the autopilot 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.

Single Unit Systems

These have a single module with dual antennas.

Note

ArduPilot allows for up to two GPSes. The following parameter examples are for setting up the first GPS instance.

NMEA

  • SERIAL3_PROTOCOL = 5 (“GPS”) assuming the GPS is connected to SERIAL3 (be sure any lower numbered port does not use this protocol unless a GPS is attached).

  • GPS_TYPE = 5 (NMEA)

Some of these systems require that the “Master” antenna and “Slave” antenna (see manufacturer’s documentation for which is antenna is designated the “Master”) be mounted on the vehicle front to back in line with the 0 degree yaw of the vehicle and at the same vertical level and be at least 30cm apart. Otherwise , the antenna offset distances in the x/y/z directions must be entered detailed in the Master-Slave Antenna Offsets section below.

Note

these units can be used with only its “Master” antenna connected, if desired, but no yaw information should be used.

Unicore UM982

  • SERIAL3_PROTOCOL = 5 (“GPS”) assuming the GPS is connected to SERIAL3 (be sure any lower numbered port does not use this protocol unless a GPS is attached).

  • GPS_TYPE = 25 (UnicoreMovingBaseline)

Note

thes units can be used with only its “Master” antenna connected, if desired, but no yaw information should be used. In this case set GPS_TYPE = 24 (UnicoreMaster)

For Unicore UM982 based GPSes, the “Master” and “Slave” antennas must be mounted at least 30cm apart on the vehicle. The offset distances in the x/y/z directions must be entered detailed in the Master-Slave Antenna Offsets section below.

DroneCAN

The antenna offset distances in the x/y/z directions must be entered detailed in the Master-Slave Antenna Offsets section below.

Master-Slave Antenna Offsets

Dual unit or single unit/dual antenna systems (except Blicube NEMA GRTK) need the relative positions for the “Master” and “Slave” antennas specified:

  • GPS_MB1_TYPE = 1 (GPS1 Moving Baseline master antenna offsets relative to slave antenna, also enables the next parameters to be shown)

  • GPS_MB1_OFS_X: offset in meters from the “Slave” to “Master” antenna in the X axis (in direction of 0 deg yaw, positive offsets are if “Master” is in front of the “Slave”.

  • GPS_MB1_OFS_Y: offset in meters from the “Slave” to “Master” antenna in the Y axis (in direction 90 deg (right) of 0 deg yaw, positive offsets are if “Master” to the right of the “Slave”.

  • GPS_MB1_OFS_Z: offset in meters from the “Slave” to “Master” antenna in the Z axis (in direction up and down, positive offsets are if “Master” below the “Slave”.

This figure and photo illustrates these parameters and their settings:

../_images/UnicoreMovingBaselineOffsets.png ../_images/X-500V2_MovingBaseline.png

Holybro X500V2 Mounting Example

RTK Correction

ArduPilot will automatically foward RTCM correction data it receives over MAVLink from a GCS or telemetry radio (from a fixed baseline RTK base station) to these GPSes. See RTK GPS Correction (Fixed Baseline).

Master Antenna Offset from Vehicle CG

For ultimate positioning precision in the centimeter ranges, the offset of the “Master” antenna from the vehicle’s CG can optionally be entered to compensate for attitude effects on GPS accuracy. The offsets from the CG are entered into:

  • GPS_POS1_X: offset in meters from the Center of Gravity to “Master” antenna in the X axis (in direction of 0 deg yaw, positive offsets are if “Master” is in front of the Center of Gravity.

  • GPS_POS1_Y: offset in meters from the Center of Gravity to “Master” antenna in the Y axis (in direction 90 deg (right) of 0 deg yaw, positive offsets are if “Master” to the right of the Center of Gravity.

  • GPS_POS1_Z: offset in meters from the Center of Gravity to “Master” antenna in the Z axis (in direction up and down, positive offsets are if “Master” below the Center of Gravity.

This figure and photo illustrates these parameters and their settings:

../_images/magoffsets.png

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