How to Setup GPS Rescue in Betaflight (FPV Drone Return to Home)


Betaflight GPS Rescue mode is similar to “Return to Home” on a DJI drone. This feature is designed to fly your FPV drone back to its launch point and land it automatically in a failsafe or when your video feed gets sketchy. In this tutorial, I’m going to walk you through setting up GPS Rescue Mode, testing it, and I’ll also share some tips on enhancing its performance and troubleshooting common issues.

Some of the links on this page are affiliate links. I receive a commission (at no extra cost to you) if you make a purchase after clicking on one of these affiliate links. This helps support the free content for the community on this website. Please read our Affiliate Link Policy for more information.

Why GPS Rescue is a Game-Changer

Betaflight’s default failsafe action is dropping the quad to the ground. Now, with the latest GPS Rescue Mode, your drone can return close to its launch point and land by itself! This is incredibly useful for long-range flights. Honestly, I’ve lost count of how many times GPS Rescue has saved my drones.

Picking the Right GPS Module

Top Performer – HGLRC M100 Mini

Smallest Worth Having GPS – GOKU GM10 Nano V3

Opting for a smaller GPS module helps save weight, but it does mean you’ll sacrifice a bit of sensitivity that comes with models with a large antenna.

Hglrc M100 Mini Gps Flywoo Goku Gm10 Nano V3 Bn220 $4 Vk2828u7g5lf

I also have good experience with the BN-220 (on average over 20 satellites within a couple of minutes). Yet, it’s equipped with the older M8 chip, meaning it generally takes longer to lock on to satellites compared to the newer M10 chips. If you are struggling to get decent performance with this GPS, you can try optimizing the settings as shown here.

Get the BN-220 here:

If you’re interested in a GPS module with an onboard compass, Flywoo has options, although it’s not necessary for Betaflight’s GPS Rescue mode to work. The modules listed above should suffice for Betaflight users.

Get the BN880 here:

Generation of GPS Chip

Most GPS modules for FPV drones use either an M8 or M10 chip. M10 chips are newer and offer better performance, capable of connecting simultaneously to four Global GNSS systems (GPS, Galileo, Glonass, and Beidou). This results in faster lock-ons and connections to more satellites, especially in areas with interference or limited sky view. Despite their superior performance, M10 units aren’t much more expensive than M8 units, making them a cost-effective upgrade.

Antenna Scratches

Noticed scratches on your GPS antenna’s metallic patch? Don’t worry; this isn’t necessarily a sign of defect or damage. It’s often the result of factory tuning to ensure optimal frequency. These types of antenna have a nominal tuned frequency, but are often impacted by construction, components location and soldering. Placing small nicks in the centre of the long edges, or corners, can fine tune its frequency.

Is a Barometer Needed?

A barometer measures altitude using air pressure, and while many flight controllers come with one built-in, e.g. the BMP280 (such as the Speedybee F405 V4 and RushFPV F722 V2), it’s not a must for GPS Rescue mode. However, having a barometer can improve altitude control. Just remember, if you’re applying conformal coating for water resistance, avoid covering the barometer.

Some GPS modules offer a built-in barometer for an extra cost. If your flight controller doesn’t have one, adding a module with a barometer could be beneficial.

Is a Compass Necessary?

A compass (as known as magnetometer in Betaflight) is for determining directions.

Some GPS modules offer built-in compass, which can be connected to the FC via the i2c port (SCL and SDA). However, Betaflight Rescue Mode doesn’t require a compass to work, it can work out its direction from GPS data.

In fact, an improperly calibrated compass might cause more issues than it solves. In my tests, Rescue mode worked perfectly fine without a compass.

How to tell if a GPS module has built-in compass? If it has 6 wires or solder pads, it means it has a compass – 5V and GND for power,  TX and RX is for the GPS, and SCL and SDA (i2c port) are for the compass. If it doesn’t have a compass, then there should only be 4 wires/pads – 5V, GND, TX and RX.

Connecting GPS to Flight Controller

Wiring a GPS module to the flight controller is quite straightforward. Simply connect it directly to any available UART on the FC, (TX to RX, RX to TX), and power it with 5V.

  • GPS RX – FC TX
  • GPS TX – FC RX
  • GPS 5V – FC 5V
  • GPS GND – FC GND
  • GPS SDA – FC SDA (if GPS has a compass/barometer)
  • GPS SCL – FC SCL (if GPS has a compass/barometer)

Avoid using Softserial for your GPS connection, as it’s limited to a 19200 baud rate. At 9600 baud, GPS reliability for Rescue Mode is compromised. A hardware serial port is your best option for a stable and reliable connection.

Gps Flight Controller Fc Connection Wiring Fpv Drone Betaflight Bn220 Bn180

Some flight controllers, like the Speedybee F405, feature 4V5 pads. These are essentially the same as 5V pads but have the added benefit of drawing power from USB. This is particularly handy for those times when the GPS is taking a while searching for satellites. By using the USB for power, you avoid the risk of your VTX overheating while waiting on the ground with a LiPo battery plugged in. It also helps the GPS lock faster since the VTX isn’t transmitting and causing interference. Note that some FCs might offer 5V pads powered by USB but under different labels; check with a multimeter if unsure.

How to Setup GPS in Betaflight

GPS Rescue mode in Betaflight is continuously evolving, so it’s crucial to use the latest firmware version for new features and bug fixes. I recommend upgrading to Betaflight v4.5 for this process: https://oscarliang.com/betaflight-4-5/

First, in the Configuration tab of the Betaflight Configurator, activate GPS for navigation and telemetry under the Other Features section. If GPS always deactivates after a reboot, it might be due to not selecting GPS in the Cloud Build options during firmware flashing.

Betaflight 4.5 Gps Rescue Setup Enable Feature Configuration

Next, in the Ports tab, assign GPS to the appropriate UART under “Sensor Input.” Betaflight supports various baud rates: 9600, 19200, 38400, 57600, 115200. If you are unsure what baudrate your GPS module supports, selecting AUTO usually works. If not, 57600 or 115200 are common rates in GPS modules.

Gps Setup Betaflight Ports Uart Auto Baud

In the GPS tab, do the following:

  • Select UBLOX as the Protocol, which is the standard for most GPS.
  • Enable Auto Config.
  • Enable Use Galileo – it improves positioning accuracy.
  • Enable Set Home Point Once to prevent resetting the home location with each arm/disarm cycle until you unplug the battery.
  • Choose Auto-detect for Ground Assistance Type to enhance positioning accuracy.
  • Save and Reboot.

Betaflight 4.5 Gps Rescue Setup Configuration Settings

After setting up, the GPS indicator at the top of the configurator should light up, indicating communication with the FC. A red icon means GPS is talking to the FC but without a lock, and a yellow icon indicates a successful GPS lock.

If the GPS indicator remains off, check for

  1. GPS is not powered? Try plugging in battery?
  2. Incorrect parameters, for instance, wrong baud rate or protocol.
  3. Incorrect wiring, try swapping TX and RX.

Betaflight 4.5 Gps Rescue Setup Top Icon Red Yellow

How to check if GPS is working?

Wondering if your GPS module is talking to the flight controller? The ‘gpspassthrough’ command in the CLI can reveal any ongoing data exchange. Seeing a stream of binary data means communication is happening.

Run the ‘gpspassthrough‘ command in the CLI can reveal any ongoing data exchange between the FC and GPS.

Seeing a stream of hieroglyphic binary data characters means communication is happening. If you see nothing, there may be an issue with power, UART connection, or your setup.

Gps U Center Betaflight Cli Serial Passthrough

Waiting for GPS Lock

Getting a GPS lock, or “3D fix,” requires locking onto at least four satellites and can take a few minutes.

When you power up the GPS module for the first time in a new location, it always takes longer to search for satellites, known as a “cold start”. Subsequent starts tend to be quicker as the module remembers satellite positions (for example when you change battery).

It’s harder to get a lock indoor. If you have to test this inside the house, try to get close to the windows with the antenna pointing to the sky.

You will see GPS related information under the GPS tab, where it shows the status of your lock, your GPS coordinates and location on a map, verifying the accuracy of your GPS lock.

Betaflight 4.5 Gps Rescue Setup Map Current Location

LED Indicators

On most GPS such as the BN220, BN180 and BN880, there are two LED indicators, labelled “TX” (usually blue) and “PPS” (usually red).

Flashing blue (TX) indicates UART connection. If it is off, then the GPS is not sending data out. This is also an indicator of the refresh rate, in 1Hz it should flash once per second, while in 5Hz it will flash 5 times a second.

Flashing red (PPS) indicates the 2D/3D fix status of the GPS. If “PPS” is off then you don’t have a fix yet.

When it gets a 3D fix, the red LED on the BN-220 module should blink (together with the blue LED).

OSD

You can display GPS info in the OSD. Check out this tutorial about Betaflight OSD if you are not familiar with it. You can display GPS coordinates, distance and direction to home and more.

Gps Osd Elements Betaflight Home Arror Direction Distance Speed Coordinates

To know how many satellite have been acquired, place the gps sats element in your OSD. 6-8 is the minimum for rescue mode to work, the more the better. Your GPS coordinates will also get more accurate when you acquire more satellites.

Gps Sats Satellites Lock Osd Element Betaflight

You can also display HDOP next to the number of satellites. HDOP is a measurement of the health of the GPS locks. A HDOP value of 1 or below is ideal, which would give you an accuracy of about 2.5 meters or less. It might be oversimplying, but just think of it as how much the drone would be drifting horizontally in meters.

To do this, go to the CLI, and enter:

set osd_gps_sats_show_hdop = on

save

Radio Telemetry

Once you have GPS setup and got a lock, go to the radio’s telemetry page, select “Discover new sensors”. Some GPS related new sensors should appear including GPS coordinates. This only works if your radio system supports Telemetry – such as ExpressLRS and Crossfire.

This allows you to log GPS coordinates in your radio, it allows you to keep track of the last known position of your aircraft. This can be helpful for searching for the lost quadcopter if you can’t see the coordinates in your DVR.

Testing Angle Mode

Betaflight’s GPS Rescue mode relies on Angle mode — a self-leveling flight mode — to stabilize the drone. Therefore, it’s essential to ensure Angle mode is functioning correctly.

First, verify that the Accelerometer is enabled in the Configuration tab.

Betaflight Configurator 10.9.0 Configuration Accelerometer Enable

Next, proceed to the Setup tab and calibrate the Accelerometer on a level surface. Failure to do so might result in the drone drifting while in Angle mode.

Betaflight Configurator Setup 10.8

To test Angle mode, try hovering the drone to see if it’s self-levelling as expected. Remember, Angle mode uses only the Accelerometer and Gyro, so it won’t keep the drone perfectly stationary like a DJI drone would. A slight drift due to weight distribution and wind is normal, as long as the drone remains stable. If drifting is noticeable, you can trim the accelerometer in the Configuration tab to minimize it (but unlikely to completely eliminate it so don’t worry).

Also, take note of the throttle position during hover. This value will be useful when setting up Rescue mode later.

Enabling GPS Rescue Mode in Failsafe

Navigate to the Failsafe tab in the Betaflight Configurator. If you can’t find this tab, make sure you’ve enabled the “Expert Mode” option at the top of the screen (next to the Update Firmware button).

Betaflight 4.3 Configurator 10.8 Expert Mode Enabled Pid Tuning

Under Stage 2, select GPS Rescue. Now, if your drone enters failsafe, it will trigger GPS Rescue Mode.

betaflight gps rescue mode failsafe

So, what exactly is failsafe, and what are stage 1 and stage 2? Here’s a quick rundown: Your drone enters failsafe upon losing radio signal. By default, it would just drop to the ground, but with Rescue Mode, it will attempt to return home.

During a failsafe, your drone will first enter Stage 1, pausing briefly (guard time) to see if the signal returns. If not, it progresses to Stage 2, activating Rescue mode to bring the quad back.

While setting GPS Rescue as your failsafe method is beneficial, it’s not suited for all environments. For instance, it’s not advisable in bando, forests, stadiums, or indoors. Losing control under a tree or inside a building could result in the drone crashing into obstacles when Rescue mode engages.

If you have no GPS lock when it failsafes, the quad will (should) just drop to the ground.

What Happens after Rescue Mode is Activated?

Watch GPS Rescue Mode in action here:

Rescue mode involves 5 phases:

  1. Ascend: The drone climbs to a predetermined altitude or the maximum altitude reached during that flight.
  2. Rotate: It turns towards the home direction.
  3. Fly Home: The drone begins its journey back to the launch point. The flight might not be a smooth cruise, exhibiting some lateral movements as it navigates home, but it will eventually arrive.
  4. Descend: Once near the launch point, within a 5x5m area, it starts descending slowly. The descent might be uneven, with the motors making pulsating sounds as the drone tries to slow down.
  5. Land: Upon touching the ground, the drone automatically disarms, with motors terminating based on impact, not based on altitude.

How to Stop Rescue Mode

If Rescue mode was activated via a switch, regaining full control is as simple as disengaging that switch.

If activated by failsafe:

  • If it’s a real failsafe triggered by a loss radio link, the pilot must move the sticks more than 30% to regain control after radio link comes back.
  • If the failsafe was triggered manually via a switch, simply disengage the failsafe switch — no need to wiggle the sticks.

GPS Rescue Settings

Settings for GPS Rescue mode are available in the Failsafe tab.

Betaflight Configurator Failsafe Gps Resuce Settings Bf 4.4

You have to tweak the settings in Betaflight to make it work for your particular setup and environment. Make sure to check out the Betaflight wiki to fully understand what the parameters do: https://github.com/betaflight/betaflight/pull/11579). The default is a pretty good starting point, which is designed primarily for 5″ freestyle drones.

Here I will go through the settings and share with you what values I use on my 5″ freestyle drone and why.

All the settings are also accessible In CLI, enter get gps_rescue and you will get a whole list of GPS related parameters. But it’s easier to change them in the GUI (in Failsafe tab).


Angle – This is the maximum angle the drone can tilt in degrees. In strong wind, you might need a higher angle to achieve the desired speed. This is especially true for smaller quads. However if the angle is too steep the drone might struggle to stay in the air so it also depends on the power of the quad. If you set a big angle you should expect some overshoot.

If you are not sure, just try the default value and see how it perform in testing.

You need to enable Accelerometer and need to be calibrated/trimmed properly for this to work accurately. If your ACC is faulty, rescue mode might not work correctly for you. Verify by flying in Angle mode.

I just leave it at default, 40, it works well for my 5″.


Initial Altitude (meters) – at what minimum height the drone returns home relative to the take off point. It should be high enough to avoid trees, buildings and power lines. But not too high it takes a long time and too much battery to ascend. I increased it to 50m as we got some tall trees and hills here.


Descend Distance (meters) – at what distance from home our drone starts to descend. I leave it at default.


Minimum distance to home (meters) – The minimum distance to home when rescue mode is allowed. There’s a hard limit in Betaflight 4.4, 20m with 2m altitude, you can’t set it lower than that.

I leave it at default, 30m.


Ground speed (meters/second) – Note when entering this value in GUI, the unit is different than CLI (which is cm/s). This is the speed at which the quad travels during Rescue. The default 5m/s is 18km/h which I find too slow, I doubled that to 10m/s which is 36km/h. The quad’s travel direction would be more accurate and update faster in higher speed (when a compass is not used and the orientation derives from GPS). Do not set it to lower than 2m/s or orientation won’t work.


Throttle minimum, Throttle maximum, Throttle hover –  these are the min, max and hover throttle values you want to use during Rescue mode. Set maximum so the quad isn’t too fast/jerky (it should be above your hover point), set min to keep the props spinning at a reasonable rate (it should be lower than your hover point).

To set hover point, you need to determine an accurate value. Test your quad and see at exactly what throttle it hovers (just enough throttle to keep the quad afloat), literally every quad is different. Use the “Throttle %” OSD element to get the exact value instead of just guessing. According to info in the pull request, “the correct value should cause the quad to climb a bit while in level mode… If these values are set too low, the quad will drop early in the rescue – possibly into the water!”.


Ascend rate, Descend rate (meters/second) – pretty self-explanatory. Adjust these based on your environment, weather condition and your quad’s power. I normally just leave it to default for my 5″ and it works pretty well. If you use Li-ion packs or low C-rating LiPo, maybe use a lower Ascend rate.


Minimum Satellites – Your quad won’t arm if the GPS has fewer satellites than this value. The recommended number of Sats is 8 for reliable rescue mode. 5 or 6 might still work, but it will be sketchy. For me it only takes a minute or two to get 10-20 satellites, so I just leave it at the default, 8.

Note that if you take off before the GPS reach the minimum amount of satellites, it won’t know where home is exactly. More satellites means better position accuracy, you can reduce the number of sats but the position accuracy will go down.

By enabling “Allow arming without fix“, you can still arm the quad when satellite locks is below the “minimum Satellites” number. I usually enable this because it’s more flexible – I don’t have to wait around when I just want some quick flights in my familiar local park. But whenever I am flying in a new spot, over water or diving down cliffs, I always wait for satellite lock.

Beware that GPS Rescue WILL NOT work for that flight if you arm before getting a satellite lock (because it doesn’t know the home position).

If you have trouble getting these many sats (or it takes a long time), check out my tutorial on how to boost your GPS receiver performance. Get a new GPS if you must, they only cost $15, a great investment for protecting your $300 quad!


Altitude Mode – it determines the altitude at which the quad returns home.

  • Maximum altitude is the highest altitude your quad is flown during that flight
  • Fixed altitude is just a user defined value
  • Current altitude is whatever height that the quad is at when GPS rescue mode is activated

The option depends on your environment. Maximum altitude is probably the safest option in my opinion, but it’s not always the right option say if you were diving a mountain in that flight, you could be wasting energy climbing back to the max altitude when Rescue mode is activated. Be adaptive to the different environment and missions.


Sanity Checks – when set to “ON”, it constantly monitors GPS Rescue mode conditions, for example:

  • is GPS still connected
  • are we getting good number of satellite fix
  • are we at least 100 meters away from home? (distance can be changed)
  • are we getting closer to the home, and we didn’t hit an obstacle

If any of these conditions are not met, it will abort rescue mode and your quad will just disarm and drop to the ground. So yea, it’s not ideal if you are flying over unrecoverable places like ocean or mountains, but generally, it should be on for safety reasons.

The Betaflight wiki also recommends setting Sanity Checks to “Failsafe Only” if you are having trouble with the option “On” during testing. It turns Sanity Checks off when Rescue mode is activated by a switch but only turns it on when it’s in failsafe. This is also my preferred option.

It’s more risky to turn off Sanity Check entirely, you might get an indefinite flyaway. In Betaflight 4.4, there is now a limit of 20s of sanity failure even if all sanity checks are off. It is a safety thing. Never fly with all sanity checks off.

How to Manually Activate GPS Rescue?

Apart from failsafe, you can also manually activate GPS Rescue by flipping a switch on your radio transmitter. It’s useful in emergency situations like losing orientation (e.g. when flying LOS) or your FPV system stops working, you can get the drone to fly back home on its own.

Go to the Modes tab and add a AUX channel for GPS Rescue Mode. Unfamiliar with the Modes tab? See my tutorial here: https://oscarliang.com/betaflight-modes/

betaflight gps rescue mode switch activate

Throttle Channel Fallback

During the stage 1 of a failsafe, the drone will go into channel fallback, which means each radio channel will be set to specific values. You might want to review these values for maximum safety.

The default Channel Fallback setting for Throttle is “Auto”, which drops the throttle to zero when Stage 1 failsafe is activated. When you change Stage 2 failsafe from the default value “Drop” to “GPS Rescue”, in the event of a failsafe the motors will momentarily stop for the Guard Time (1.5 seconds by default in BF4.4). This might destabilize the quad while GPS Rescue kicks in, and Betaflight thinks there’s something wrong as it fails one of the sanity checks and cause the drone to just drop to the ground.

A workaround would be to set the Throttle Channel Fallback setting  from “Auto” to “Hold”, so the throttle value is held at its last commanded position for the Guard Time to avoid the motor stalling.

Even better, I normally set throttle to the hover throttle value, center all the roll/pitch/yaw sticks, and put the quad in Angle mode, so as soon as Failsafe happens the quad just levels out and stays there until Rescue mode kick in (if my radio signal doesn’t come back).

Never set throttle to zero in stage 1 failsafe!

Betaflight Configurator Failsafe Gps Resuce Settings Bf 4.4

How to Test GPS Rescue

Here’s how I would test GPS Rescue.

First of all, assign a switch to GPS Rescue and make sure it can indeed bring your quad home as intended. If anything goes wrong, disengaging the switch should give you full control again.

Next, assign a switch to Failsafe in the Modes tab in Betaflight. It emulates full failsafe mode in Betaflight (just like when you lose RC signal). This is a lot safer than testing by turning off your radio, because you can disengage anytime you want using a switch.

Note that this is only for testing GPS Rescue mode, as soon as you finish testing, you should remove it in the modes tab.

Betaflight Configurator Modes Failsafe

Remove all props, go into the Modes tab and verify that Failsafe mode can actually get activated by the switch. At this point your quad will go into Rescue mode, and your radio controls will be locked out. Now check if you can deactivate failsafe and take back control.

When you are testing this on the bench, with the USB cable connected, the Rescue mode box won’t turn yellow like other modes. This is fine as long as the small yellow bar can move to the activation range.

It’s useful to have these GPS related info on your OSD, they will help you understand what your quad is doing. You can also have Flight Mode enabled, it’ll say “RESC” when Rescue mode is activated, “Air” when your quad is in rate mode, and “Angle” when it’s in angle mode.

Now test it in an open field with no obstacles and people.

Make sure you have enough locked satellites in the OSD before arming.

Fly in a straight line, 100-200 meters away.

Activate Failsafe mode using the switch, shortly your quad should enter GPS Rescue mode (watch the flight mode in OSD).

Pay attention to the home arrow in Betaflight OSD, if it’s pointing up, it means you are flying home. If it’s pointing down, means you are flying away from home. The arrow might be pointing the wrong direction at the beginning, this is normal. Just make sure the quad isn’t flying the complete opposite direction.

You can quit failsafe mode by flipping the switch at any time and resume full control.

If you don’t disengage, it will carry on flying home. When the quad reaches home, it will hover for a bit and starts to slowly descend but the motors will be pulsating… until it hits the ground and disarms automatically.

Repeat the procedure again and again until you are feeling comfortable with it.

Once you are done with testing, remove Failsafe from the Modes tab.

Tips

Best Places to Mount GPS Module

Make sure the GPS eramic patch antenna has a clear view of the sky for locking onto satellites, and nothing is covering it which can weaken GPS signal, especially conductive materials such as carbon fibre, electrical wires, and metal.

Avoid EMI from other electrical components on your quad. Common RF interference sources that can impact GPS performance are HD camera and video transmitter. Mount your GPS as far away from these devices as possible.

One common mistake is mounting the GPS upside down. The GPS receiver antenna should be facing up, it’s a flat square with small metal circular part in the middle. There should be no components at all on this side. As an example, this is the ceramic antenna in a GPS receiver, it should be facing up.

Holybro Nano Ublox M8 5883 Gps Module

Make sure there’s nothing blocking or interfering with the GPS unit at anytime. Mount it on top of your quad, as far away from the VTX /  RX antennas as possible (many radio receivers can actually transmit signal as well due to their two-way communication nature when telemetry is enabled). Also beware some HD cameras might produce radiation that can affect your GPS signal as well if they don’t have the appropriate shielding.

Here are some ideas where/how to mount the GPS module in an FPV drone.

Hglrc Sector X5 Bnf Fpv Drone Rx Vtx Antenna Gps 3d Print

Stp Hobby Armor 5 Fpv Drone Rushfpv Rx Vtx Antenna Gps Mount

On top of your GoPro/HD camera.

On top of your frame if you have an under-slung battery.

Using a mast to keep the GPS as far away from the quad as possible. But probably a bad idea to have it so close to the VTX antenna in this example…

The rule of thumb is that the GPS must see the sky at all times (except when you are doing a roll or inverted yaw spin).

Before your flight, it can take a while to get a GPS lock. You might want to power on your quad and GPS beforehand to “warm up” first, e.g. on the way to the flying field.

How to Get a GPS Lock Faster

Most GPS modules have a small battery, which is used to store satellite information and time for a faster lock.

After the GPS module gets a satellite lock, it remembers all the satellite locations, so after you change the drone’s battery (the GPS module is powered off briefly), the GPS lock usually can resume almost immediately. But when the GPS doesn’t have satellite information stored in memory, or the satellites it remembers are no longer in view, it will take much longer to get a lock.

This is why some people powered on their quad (or just the GPS module) prior to their flight just to get a lock, so they don’t have to wait around before taking off.

If your GPS always takes a long time to get a lock, it’s worth checking if the battery is dead (with a multimeter). Also make sure there is as little interference to the GPS as possible, for example if you are using1.3GHz FPV setup, try moving powerful VTX away from the GPS. Cloudy day can also have an effect on GPS signal quality.

Also check out my post about optimizing GPS settings to get more satellite locks.

Words from Betaflight Devs

I recommend 10 satellites. [And] Wait for 30s after [you have] 10 satellites for altitude to stabilise [before taking off].

Always confirm normal GPS Rescue behaviour at the start of a critical flight by testing with the failsafe switch. Set the switch to immediately enter Stage 2. You can enter and leave GPS Rescue via the switch with immediate on and off effect. Check that the quad rotates and flies towards home and does the right things before you are so far away that a true failsafe may occur.

ALWAYS CHECK that the Home Arrow points directly back towards home after takeoff! Sometimes, if you take off and spin around during arming or immediately on takeoff, the quad’s attitude information can become corrupted, and the Home Arrow can point the wrong way. It’s best to arm cleanly and fly away from Home in a straight line at a reasonable speed immediately after takeoff. Watch the Home Arrow carefully to ensure it quickly points back to Home. If the Home Arrow points the wrong way when a failsafe occurs, the GPS Rescue will initially fly off in the wrong direction, and in some cases, you may lose the quad.

Wrong direction in Rescue?

Without a compass, your quad can still work out direction using GPS coordinates. By flying forward the drone can calculate which way it’s going by comparing the current position and the previous position. That’s why at the beginning, your quad might be wandering around or even flying towards the wrong direction but eventually it should correct itself. If your GPS signal is weak or updating too slowly it can take longer to correct.

If you are using a compass and it’s flying the wrong direction, then maybe there’s something wrong with the compass, or maybe it’s not calibrated properly. In this case try turning off the magnetometer (compass) and try again. If it works now, it proves your compass is the source of the problem.

If your yaw is jerky during Rescue mode, your GPS might be updating too slowly (e.g. 1Hz), try to increase it to 5Hz or even 10Hz following this guide (only works on certain GPS modules).

Avoid Softserial

Avoid using Softserial for GPS, as it only supports up to 19200 baud rate, and with 9600 baudrate the GPS is simply not reliable enough for GPS operations. It’s best to use a hardware serial port (any TX and RX pins on the FC), and set baudrate to at least 57600.

Not Getting GPS Lock

Interference from other electronics such as your VTX, radio receiver if you have telemetry, or even nearby wires that carry a lot of current can prevent the GPS from getting a lock. If you have trouble getting a GPS lock, try the following:

  • Try to power your FC from USB and see if that powers up your GPS module. If not, try to move your GPS module power to another pad on the FC that gets power from the USB port
  • Powering only the FC without the VTX should make it easier for the GPS to get a lock, once you get a lock, it should stay locked normally even when the VTX is powered on. But it’s still a good idea to mount your GPS as far away from VTX antenna and RX antenna as possible
  • Shielding nearby wires can also help sometimes. Wires carrying current are like antennas, they could also potentially mess with GPS

GPS satellites transmit data on two frequencies, L1 1575.42MHz and 1227.60MHz, hence 1.3GHz FPV can cause interference to your GPS. Most people run 5.8GHz so this shouldn’t be an issue. But since GPS signal is so weak (it’s all the way from space after all), any powerful signal nearby can cause interference, therefore you should mount the GPS module as far away from any transmitting sources as possible.

When you run your GPS wires to the FC under the VTX, it can also cause issues as certain VTX’s don’t have proper RF shielding and the RF noise is enough to mess up your GPS. For example the Avatar VTX is known to cause GPS issue when running wires under it. Solutions could be properly grounding the VTX shielding, but you could also try to shield the wires between the GPS and FC, and make sure to ground it.

Gps Wire Cable Ground Shielding Foil Betaflight Fc

I tried shielding the wires with some foil in one of my quads, then connect the foil to a ground pad on the FC (to ground it). Finally wrap it with some cloth tape so it doesn’t short the frame. Some people reported good result with this modification, for me the improvement is little, but it’s worth a shot if there’s no other easy solution.

Can’t enable GPS after flashing Betaflight

It’s possible that GPS was excluded from the compiled firmware due to the new Cloud Build system in Betaflight 4.4.

To confirm this is the case, enter this command in CLI:

feature gps

If CLI returns “gps not available”, then it means the GPS feature isn’t part of the betaflight firmware in your FC. In this case you will have to reflash your FC, this time you should make sure GPS included in the Cloud build system option when compiling it.

GPS Coordinates Decimals

To display GPS coordinates in the OSD you have the options to select how many decimals to display (currently only 4 and 7 decimals are available). It affects how precise the position is when you search for the coordinates on a map.

On Wikipedia page “Decimal Degrees” there’s a table on Degree Precision vs. Length.

decimal
places   degrees          distance
-------  -------          --------
0        1                111  km
1        0.1              11.1 km
2        0.01             1.11 km
3        0.001            111  m
4        0.0001           11.1 m
5        0.00001          1.11 m
6        0.000001         11.1 cm
7        0.0000001        1.11 cm
8        0.00000001       1.11 mm

Beware of the difference between accuracy and precision. Your GPS may report any number of digits (its precision) but many of the decimal places might be just erroneous (accuracy)1.

Edit History

  • Oct 2018 – tutorial created
  • Aug 2020 – updated, GUI changes, CLI parameter names changes, added throttle min/max/hover values
  • Feb 2023 – updated for BF4.4 (with auto landing capability)
  • Mar 2024 – updated for BF4.5

Latest articles

spot_imgspot_img

Related articles

Leave a reply

Please enter your comment!
Please enter your name here

spot_imgspot_img