Skip to content

GPS and Compass setup

Jetrell edited this page Feb 6, 2024 · 27 revisions

In post 7.0 releases. INAV only supports Ublox and Ublox7 protocols.

Recommended GNSS units are M8, M9 or M10 models for best navigation performance.

Modules known to work reasonably well:

Older versions as M6N and M7N also work, but the newer M10 versions are far superior. Most GPS modules have a built in magnetometer (compass), but there are also some available without e.g. Matek M10Q or Beitian BN-220 which are perfect for planes and flying wings.

With default settings INAV will configure the GPS automatically, there is no need for configuring it manually using software like u-center. Nevertheless you have to configure your FC with INAV to receive the GPS signals.

For INAV before 1.9, it is also necessary to perform some manual configuration of UBLOX 3.01 firmware GPS to use Galileo satellites.

With INAV 7.0 and later, GPS, Galileo and BeiDou or Glonass (not both) can be enabled in the GPS configuration tab (GPS is ON by default).

If you want to use the external magnetometer (built in your GPS) and you have a FC with the same magnetometer (HMC5883L is very common), you have to disable it physically on your FC: remove chip from board or cut a trace. You can't use two identical chips/magnetometers on the same I2C bus.

  • When using DJI NAZA gps this is not the case, DJI NAZA sends compass over serial and does not use the I2C bus)
  • On MPU9250 board internal magnetometer is an AK8963, most GPS pucks are HMC5883L. So no need to remove hardware, only choose which one to use with cli command mag_hardware
  • Recent MATEK M10 compass is provided over serial MSP

If you elect to use the internal FC magnetometer you are highly likely to have poor results due to magnetic interference (not recommended).

INAV 7.1 changes

From the release of INAV 7.1. The use of a compass is no longer mandatory for multirotor navigation as it once was. BUT is still recommended for best performance when it comes to maintaining a fixed position for an extended period of time, without heading drift. e.g. in Poshold. Or taking off and immediately starting a Waypoint mission.

  • Compass-less navigation performance is heavily dependent on clean build.. Having minimal levels of Gyro/Acc noise.. It may not work correctly if your multirotor is producing excessive vibrations, caused by unbalanced motors, propellers or frame resonance.

INAV 7.1 will also offer better compass interference rejection. But this is not an excuse to be tardy on your install, or shortcut the calibration process.

If a user does decide to omitted the use of a compass for a multirotor.. For reasons like the models size or magnetic interference that can not be overcome. Be mindful that any navigation mode (RTH, Failsafe, Poshold, Cruise or a Waypoint mission) will not be operational UNTIL a GPS heading is first obtained, by flying in a straight line until -

  • The OSD Heading or Course over Ground indicator displays a valid heading.
  • The OSD Home arrow provides direction

Only then can the IMU heading estimator data be trusted for slow speed or fixed position navigation. Be certain this is the case before you depend on RTH.

INAV 7.1 and later will also benefit fixedwing models by the use of a compass, in providing better heading estimation.. While in previous releases a compass provided no extra benefit.

Installing the GPS unit - Antenna orientation

To avoid confusion over the antenna orientation, ensure the antenna is skywards as follows:

Sky side
TOP_bn-880 Antenna upwards
Ground side
BOTTOM_bn-880 Connector on the bottom (downwards)

Setting up the compass alignment

Before attempting any MR navigation modes, you should verify that the compass alignment is correct (Configurator or CLI set align_mag)

  • Perform any tests away of sources of magnetic interference. Domestic appliances or even audio speakers can cause erroneous affects.
  • Use an analogue compass in preference to a digital (mobile phone) compass. The compass in your phone is likely to be a similar chip to that on your aircraft, and is as susceptible to errors of interference and calibration
  • Alternatively, if you know the orientation of surrounding landmarks (e.g. my house is pretty much N/S), then you can do static tests against land orientation.

Check your machine at cardinal points (North (0°), East (90°), South (180°), West (270°)). Degree perfect alignment is not necessary (and probably not measurable), but you should aim for +/- 5° of known magnetic direction.

  • If the values are incorrect by a multiple of 90°, then the numeric alignment needs to be changed

  • If the values are just randomly wrong across the cardinal points, then FLIP is probably wrong (as well).

  • If external Compass module is mounted at 30 degree. For example at top of a Cam mount, free alignment is possible by Cli commands. Cli setting Align_mag must be set to Align_mag = default save

For example cw270flip, this value is to ADD manualy. For free Alignment, all three axis need to set manualy. A sensor flip is always to realise over the pitch axis. For example cw270flip:

set align_mag_pitch = 1800
set align_mag_roll = 0
set align_mag_yaw = 2700
save
  • For 30 Degree Backwards tilted GPS/Compass Module, reduce align_mag_roll about 300

    set align_mag_roll = -300 save

  • Because Magnetometer with cw270° has its roll axis in relation to the Pitch Axis of the FC

Enhanced Explanation in #6232 How to Align and Check if your readings are Correct

Painless360 done a superior Video on this Setup non Flat mounted External Compass. (Tilted)

There is an online (web based) software tool to help with alignment Alignment Tool; this tool is built into the INAV configurator for INAV 5.0 and later.

Initial flight tests

Once you're content that the static configuration of the compass is correct, it's time to go flying. There is still no guarantee that the machine will not generate interference, so it's advisable to do some controlled testing before attempting more advanced navigation modes:

  • In a clear space (no trees!) attempt a simple line of sight POSHOLD. If the craft fails to hold (toilet bowling, or ever increasing circles (in range and speed)), be prepared to disengage PH and take manual control.

To confirm magnetic interference, blackbox logging is most useful:

  • Fly at a reasonable speed (> 5m/s) in straight lines, as close as possible to a 90° crossing paths, or a square / rectangular pattern.

  • The blackbox can be analysed to compare the course over the ground (from GPS) with the compass readings (GPS_ground_course v. attitude[2]/10). Run blackbox_decode with the --merge-gps option to get GPS fields in the log.

  • If you need help doing this, post the log in the INAV RC Groups forum (or Discord / Telegram channel) and ask for help. There are a number of users familiar with this type of analysis who can assist.

  • It is necessary to fly at a reasonable speed in order to get useful GPS data. Just hovering is not useful as the GPS cannot detect direction without movement.

  • If you use mwp as a ground station with telemetry, then mwp logs can also provide useful analysis, but blackbox is preferred, as there is more data and it is also possible to analyse throttle affects.

Only when you're content that the compass reads correctly for all throttle settings and directions should you progress to more advanced navigation feature (way points, return to home). The majority of navigation failures are due to poorly performing compasses.

Getting started with Ublox GPS

  • Physically connect your GPS to your FC using UART (preferred) or softserial (not recommended). Connect RX from GPS to TX on FC, TX from GPS to RX on FC

  • Activate GPS in the ports tab in INAV configurator and set it to 57600 or 115200 using UART or 19200 using softserial (on your chosen port)

  • Activate GPS in the configuration tab, set it to ublox.

  • Using external compass:

  • Connect the magnetometer to I2C ports (SCL/SDA) Be aware that with SDA/SLC lines connected the flight battery must often be connected to access configurator and power up the magnetometer.
  • Select your newly connected magnetometer by using mag_hardware CLI command. Example set mag_hardware = auto if you only have one magnetometer connected.
  • Most built in magnetometers are on the underside and rotated 180 degrees, use example set align_mag = CW180FLIP. If compass is not working properly in all directions then either think and figure out the direction of your mag, or go through them all until it works as expected.
  • F3 based board and newer uses default automatic magnetic declination, if your on F1 board or want to change magnetic declination manually you have to set correct declination of your spesific location, which can be found here: www.magnetic-declination.com. If your magnetic declination readings are e.g. +3° 34' , the value entered in the INAV configurator is 3.34 (3,34 in some locales). In the CLI, the same effect would be set mag_declination = 334. For west declination, use a minus value, e.g. for 1° 32' W, set mag_declination = -132. In all cases (both CLI and GUI), the least significant digits are minutes, not decimal degrees.
  • Calibrate your compass according to compass calibration

Note to change magnetic declination manually on F3 or later board you have to turn off automatic function. set inav_auto_mag_decl = OFF.

NEO-M8N PixHawk GPS Unit / BN-880

A readily available GPS unit is the "NEO-M8N" unit that is available from eBay, Amazon, Banggood & so on...

They are cheap and use multiple satellite networks in addition to GPS (GLONASS, Galileo) so obtaining a GPS fix is quicker and you can be flying around with anywhere between 15 to 30 satellites.

Also as a bonus with such units they have a magnetometer (a compass) on the underside of the board too!

BN-880_arrow

An important note is that on top of the protective shell of the MN-M8N there is an arrow, this needs to point towards the front of your model. The BN-880 plug needs to point down and to the rear of your model. It is also recommended to encase the BN-880 as it is quite fragile.

Important: You need to switch the Rx and Tx wires around. So you connect your GPS Tx wire (yellow) to your desired Rx pin and the GPS Rx wire (White) to your Tx pin on your flight controller.

A video showing you how to do this for a Omnibus F4 V2 board is in this video on YouTube

Other boards (e.g. MATEK) may not power 5V when on USB. In order to power the GPS it is necessary to connect the battery or use another power source (a 4.5V source may be powered by USB). The onboard 3.3V will be powered by USB, but may not provide adequate voltage, as the GPS regulator typically requires 3.6V minimum.

Once you have connected the GPS to your flight control board

  • Open the INAV Configurator
  • Enable GPS on your desired UART port
  • Set the the baud rate to 115200
  • Press "Save & Reboot"
  • Then go to the "Configuration" tab in the INAV Configurator
  • Enable GPS
  • Set the "Protocol" to UBLOX7
  • Set the "Ground Assistance Type" to "Auto Detect"
  • set MAG Alignment to CW270FLIP
  • Press "Set & Reboot" You can confirm the GPS unit is working by going to the GPS tab in the INAV Configurator and if it is working you will see the "Total Messages" count on the left incrementing in numbers.

If it is the first time you have connected the GPS unit, then it can take several minutes for a GPS fix to be obtained. This is perfectly normal.

Note: For the GPS unit to work & pick up satellites it needs an unobstructed view to the sky (so if using indoors, don't expect any satellites to be picked up!)

Getting started with DJI NAZA GPS

  • Physically connect your GPS to your FC using UART. Connect RX from GPS to TX on FC, TX from GPS to RX on FC

  • Activate GPS in the ports tab in INAV configurator and set it to 115 200 on correct UART

  • Type this in CLI

    feature GPS set gps_provider = NAZA set mag_hardware = GPSMAG set align_mag = CW180FLIP

Default DJI GPS puck pointing forward is set with CW180FLIP, but can be changed with CW0FLIP, CW90FLIP, CW180FLIP or CW270FLIP

  • Inav since 1.5 version and newer uses default automatic magnetic declination, if your on old verion or want to change magnetic declination manually you have to set correct declination of your spesific location, which can be found here: www.magnetic-declination.com. If your magnetic declination readings are e.g. +3° 34' , the value entered in the INAV configurator is 3.34 (3,34 in some locales). In the CLI, the same effect would be set mag_declination = 334. For west declination, use a minus value, e.g. for 1° 32' W, set mag_declination = -132. In all cases (both CLI and GUI), the least significant digits are minutes, not decimal degrees.
  • Calibrate your compass according to compass calibration

Note to change magnetic declination manually on F3 or newer board you have to turn off automatic function. set inav_auto_mag_decl = OFF.

Thats it!

SBAS

When using a UBLOX GPS the SBAS mode can be configured using gps_sbas_mode.

The default is AUTO.

Value Region
AUTO Global
EGNOS Europe
WAAS North America
MSAS Asia
GAGAN India
SOUTHPAN Australia NZ
NONE NONE

If you use a regional specific setting you may achieve a faster GPS lock than using AUTO, but keep in mind to change it if you change your location for holidays etc.

This setting only works when gps_auto_config= ON

Issues

  • X! in the OSD GPS Satellites field indicates the flight controller isn't receiving a valid data signal from the GPS.
  • No GPS lock: often due to electric noise from flight controller or other equipment such as 1.2ghz video TX. Try getting the GPS as far away as possible from electric noise emitting parts as the FC, ESCs or power cables. Placing the GPS on a mast is also a common way, you can further try shielding with aluminum or copper foil. Don´t place the GPS inside the frame.
  • "Toilet bowling": in the beginning the copter holds its position and then starts to make bigger and bigger circles, you probably have your magnetometer not calibrated correctly or it’s interfered from the magnetic field of your power lines or the beeper. If you are using your FC onboard mag, try to place the the FC as far away as possible from the magnetic interference causing parts e.g. mounting it on/under the top plate on small racers.
  • 3.3V GPS units, such as the GPS from 3DR should not be powered by the flight controller's 3.3V pin along with a Spektrum (or other DSM) receiver. The current draw can cause the Spektrum receiver to brownout. Instead use a 3.3V regulator and power the GPS from the BEC or separate battery.

WIKI TOPICS

Wiki Home Page

INAV Version Release Notes

7.1.0 Release Notes
7.0.0 Release Notes
6.0.0 Release Notes
5.1 Release notes
5.0.0 Release Notes
4.1.0 Release Notes
4.0.0 Release Notes
3.0.0 Release Notes
2.6.0 Release Notes
2.5.1 Release notes
2.5.0 Release Notes
2.4.0 Release Notes
2.3.0 Release Notes
2.2.1 Release Notes
2.2.0 Release Notes
2.1.0 Release Notes
2.0.0 Release Notes
1.9.1 Release notes
1.9.0 Release notes
1.8.0 Release notes
1.7.3 Release notes
Older Release Notes

QUICK START GUIDES

Getting started with iNav
Fixed Wing Guide
Howto: CC3D flight controller, minimOSD , telemetry and GPS for fixed wing
Howto: CC3D flight controller, minimOSD, GPS and LTM telemetry for fixed wing
INAV for BetaFlight users
launch mode
Multirotor guide
YouTube video guides
DevDocs Getting Started.md
DevDocs INAV_Fixed_Wing_Setup_Guide.pdf
DevDocs Safety.md

Connecting to INAV

Bluetooth setup to configure your flight controller
DevDocs Wireless Connections (BLE, TCP and UDP).md\

Flashing and Upgrading

Boards, Targets and PWM allocations
Upgrading from an older version of INAV to the current version
DevDocs Installation.md
DevDocs USB Flashing.md

Setup Tab
Live 3D Graphic & Pre-Arming Checks

Calibration Tab
Accelerometer, Compass, & Optic Flow Calibration

Alignment Tool Tab
Adjust mount angle of FC & Compass

Ports Tab
Map Devices to UART Serial Ports

Receiver Tab
Set protocol and channel mapping

Mixer

Mixer Tab
Custom mixes for exotic setups
DevDocs Mixer.md

Outputs

DevDocs ESC and servo outputs.md
DevDocs Servo.md

Modes

Modes
Navigation modes
Navigation Mode: Return to Home
DevDocs Controls.md
DevDocs INAV_Modes.pdf
DevDocs Navigation.md

Configuration

Sensor auto detect and hardware failure detection

Failsafe

Failsafe
DevDocs Failsafe.md

PID Tuning

PID Attenuation and scaling
Fixed Wing Tuning for INAV 3.0
Tune INAV PIFF controller for fixedwing
DevDocs Autotune - fixedwing.md
DevDocs INAV PID Controller.md
DevDocs INAV_Wing_Tuning_Masterclass.pdf
DevDocs PID tuning.md
DevDocs Profiles.md

GPS

GPS and Compass setup
GPS Failsafe and Glitch Protection

OSD and VTx

DevDocs Betaflight 4.3 compatible OSD.md
OSD custom messages
OSD Hud and ESP32 radars
DevDocs OSD.md
DevDocs VTx.md

LED Strip

DevDocs LedStrip.md

ADVANCED

Advanced Tuning

Fixed Wing Autolaunch
DevDocs INAV_Autolaunch.pdf

Programming

DevDocs Programming Framework.md

Adjustments

DevDocs Inflight Adjustments.md

Mission Control

iNavFlight Missions
DevDocs Safehomes.md

Tethered Logging

Log when FC is connected via USB

Blackbox

DevDocs Blackbox.md
INAV blackbox variables
DevDocs USB_Mass_Storage_(MSC)_mode.md

CLI

iNav CLI variables
DevDocs Cli.md
DevDocs Settings.md

VTOL

DevDocs MixerProfile.md
DevDocs VTOL.md

TROUBLESHOOTING

"Something" is disabled Reasons
Blinkenlights
Pixel OSD FAQs
TROUBLESHOOTING
Why do I have limited servo throw in my airplane

ADTL TOPICS, FEATURES, DEV INFO

AAT Automatic Antenna Tracker
Building custom firmware
Default values for different type of aircrafts
Features safe to add and remove to fit your needs.
Developer info
INAV MSP frames changelog
INAV Remote Management, Control and Telemetry
Lightweight Telemetry (LTM)
Making a new Virtualbox to make your own INAV
MSP Navigation Messages
MSP V2
OrangeRX LRS RX and OMNIBUS F4
Rate Dynamics
Target and Sensor support
UAV Interconnect Bus
Ublox 3.01 firmware and Galileo
DevDocs 1wire.md
DevDocs ADSB.md
DevDocs Battery.md
DevDocs Buzzer.md
DevDocs Channel forwarding.md
DevDocs Display.md
DevDocs Fixed Wing Landing.md
DevDocs GPS_fix_estimation.md
DevDocs LED pin PWM.md
DevDocs Lights.md
DevDocs OSD Joystick.md
DevDocs Servo Gimbal.md
DevDocs Temperature sensors.md

OLD LEGACY INFO

Supported boards
DevDocs Boards.md
Legacy Mixers
Legacy target ChebuzzF3
Legacy target Colibri RACE
Legacy target Motolab
Legacy target Omnibus F3
Legacy target Paris Air Hero 32
Legacy target Paris Air Hero 32 F3
Legacy target Sparky
Legacy target SPRacingF3
Legacy target SPRacingF3EVO
Legacy target SPRacingF3EVO_1SS
DevDocs Configuration.md
Request form new PRESET
DevDocs Introduction.md
Welcome to INAV, useful links and products
iNav Telemetry
DevDocs Rangefinder.md
DevDocs Rssi.md
DevDocs Runcam device.md
DevDocs Serial.md
DevDocs Telemetry.md
DevDocs Rx.md
DevDocs Spektrum bind.md

Clone this wiki locally