Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

GPS Fix estimation (dead reconing, RTH without GPS fix) for fixed wing #8347

Merged
merged 83 commits into from
Dec 8, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
83 commits
Select commit Hold shift + click to select a range
f87c081
gps fix estimation squashed commit
RomanLut Aug 21, 2022
00b5085
Update GPS_fix_estimation.md
RomanLut Aug 21, 2022
ccfa58e
included fixed USER3 BOX ID collision
RomanLut Aug 21, 2022
2272b6e
Merge branch 'submit-gps-fix-estimation' of https://github.com/RomanL…
RomanLut Aug 21, 2022
b276d26
Merge branch 'master' of https://github.com/RomanLut/inav into submit…
RomanLut Aug 22, 2022
ffa28d8
updated documentation
RomanLut Aug 22, 2022
7de16ff
retrigger checks
RomanLut Aug 22, 2022
2f6a192
retrigger checks
RomanLut Aug 22, 2022
9f0489e
retrigger checks
RomanLut Aug 22, 2022
e93145e
Merge branch 'master' of https://github.com/RomanLut/inav into submit…
RomanLut Aug 22, 2022
e4ff863
fixed rename getAirspeedEstimate()
RomanLut Aug 22, 2022
ccad410
retrigger checks
RomanLut Aug 22, 2022
bd5a92c
retrigger checks
RomanLut Aug 22, 2022
2b83b16
Update GPS_fix_estimation.md
RomanLut Sep 26, 2022
cb2d448
Merge branch 'master' of https://github.com/RomanLut/inav into submit…
RomanLut Dec 10, 2022
1ed4c3e
Merge branch 'submit-gps-fix-estimation' of https://github.com/RomanL…
RomanLut Dec 10, 2022
a439e29
adjusted docs
RomanLut Dec 10, 2022
3ade7e2
fixed typo in comment
RomanLut Dec 28, 2022
01ada27
added failsafe_gps_fix_estimation_delay
RomanLut Dec 28, 2022
731b16c
Merge branch 'master' of https://github.com/RomanLut/inav into submit…
RomanLut Dec 28, 2022
dfd9dff
Update GPS_fix_estimation.md
RomanLut Dec 29, 2022
064a8ee
Merge branch 'master' of https://github.com/RomanLut/inav into submit…
RomanLut Feb 14, 2023
bf3a857
Update GPS_fix_estimation.md
RomanLut Feb 15, 2023
637f072
Merge branch 'submit-gps-fix-estimation' of https://github.com/RomanL…
RomanLut Feb 19, 2023
dc71194
show pitot failure status on osd
RomanLut Feb 27, 2023
7591ed5
enable possibility to simulate GPS sensor timeout, mag failure and pi…
RomanLut Feb 26, 2023
e602707
fix GPS timeout display on OSD
RomanLut Mar 5, 2023
ce9cbd1
estimate GPS Fix only if compass and barometer are healthy
RomanLut Mar 5, 2023
12cb0c5
support GPS Fix estimation on sensor timeout
RomanLut Mar 6, 2023
a62bc74
Update GPS_fix_estimation.md
RomanLut Mar 6, 2023
6e7dafb
fixed compilation error
RomanLut Mar 6, 2023
caa048c
Merge branch 'submit-gps-fix-estimation' of https://github.com/RomanL…
RomanLut Mar 6, 2023
f0d5358
Merge branch 'master' of https://github.com/RomanLut/inav into submit…
RomanLut Mar 6, 2023
064c6e2
Merge branch 'submit-simulator-sensor-failures' of https://github.com…
RomanLut Mar 6, 2023
7afaa0d
fixed indentation
RomanLut Mar 6, 2023
69a1220
fixed indentation
RomanLut Mar 6, 2023
f9e078f
fixed indentation
RomanLut Mar 6, 2023
4c39d77
removed debug code
RomanLut Mar 6, 2023
2ce2904
attempt to fix failsafe_gps_fix_estimation_delay bug
RomanLut Mar 6, 2023
a10b7ce
enable ground course estimation
RomanLut Mar 8, 2023
20cdfc8
fixed landing detection with GPS fix estimation
RomanLut Mar 8, 2023
ec5e0c8
fixed: forced RTH is not activated on GPS Fix estimation event during…
RomanLut Mar 8, 2023
0fb2c1e
Merge branch 'master' of https://github.com/RomanLut/inav into submit…
RomanLut Apr 5, 2023
44fea0e
fixed merge conflict
RomanLut Apr 5, 2023
cc39912
fixed: groundspeed is not sent in mavlink telemetry
RomanLut Apr 25, 2023
9796bbb
use any wind estimator value with gps fix estimation
RomanLut Apr 27, 2023
55fdeae
improved course hold with GPS Fix estimation
RomanLut Apr 27, 2023
46150ad
Merge branch 'master' of https://github.com/RomanLut/inav into submit…
RomanLut Apr 27, 2023
4d888e4
fixed gpsSol access race conditions
RomanLut May 19, 2023
8c933ed
fixed HITL HW sensors failure simulation
RomanLut Apr 28, 2023
7d007a5
use wind vector for course correction on estimation on gps timeout
RomanLut May 19, 2023
cdd299f
fixed gps fix estimation on gps timeout
RomanLut May 19, 2023
3040cd7
return 99 satellites for logic condition on estimation
RomanLut May 19, 2023
daac5b5
removed redundand code
RomanLut May 19, 2023
f18b5a0
allow course correction on estimation with gps sensor timeout
RomanLut May 19, 2023
7e777fa
Update GPS_fix_estimation.md
RomanLut May 19, 2023
221d300
Merge branch 'master' of https://github.com/RomanLut/inav into submit…
RomanLut May 20, 2023
d5187ed
Merge branch 'submit-gps-fix-estimation' of https://github.com/RomanL…
RomanLut May 20, 2023
ff1cd25
fixed compilation error
RomanLut May 20, 2023
8778980
Update GPS_fix_estimation.md
RomanLut Jul 7, 2023
2b9a5a6
Merge branch 'master' of https://github.com/RomanLut/inav into submit…
RomanLut Aug 3, 2023
5eb46f5
Update GPS_fix_estimation.md
RomanLut Aug 4, 2023
8b1330c
Update GPS_fix_estimation.md
RomanLut Aug 4, 2023
ee66d0f
Update GPS_fix_estimation.md
RomanLut Aug 4, 2023
ae5c144
Update GPS_fix_estimation.md
RomanLut Aug 4, 2023
599e45c
added USE_GPS_FIX_ESTIMATION
RomanLut Aug 9, 2023
9e6df5f
Merge branch 'submit-gps-fix-estimation' of https://github.com/RomanL…
RomanLut Aug 9, 2023
4602a83
fixed unit test error
RomanLut Aug 9, 2023
dc1d2e8
ignore project file
RomanLut Aug 9, 2023
86b875d
allow gps fix estimation without compass
RomanLut Sep 3, 2023
6168348
Update GPS_fix_estimation.md
RomanLut Sep 3, 2023
713b521
Update GPS_fix_estimation.md
RomanLut Sep 3, 2023
0829ef6
Update GPS_fix_estimation.md
RomanLut Sep 3, 2023
3ee200d
Update GPS_fix_estimation.md
RomanLut Sep 3, 2023
f05dcc1
Update GPS_fix_estimation.md
RomanLut Sep 3, 2023
9cd68b1
Merge branch 'master' of https://github.com/RomanLut/inav into submit…
RomanLut Sep 3, 2023
8a1dd1c
Merge branch 'submit-gps-fix-estimation' of https://github.com/RomanL…
RomanLut Sep 3, 2023
b7745af
fixed compilation error
RomanLut Sep 3, 2023
e4453c3
Merge branch 'master' of https://github.com/RomanLut/inav into submit…
RomanLut Sep 30, 2023
a08e8c4
Merge branch 'master' of https://github.com/iNavFlight/inav into subm…
RomanLut Oct 27, 2023
9a633d1
Merge branch 'master' of https://github.com/iNavFlight/inav into subm…
RomanLut Nov 3, 2023
f3359ef
Update GPS_fix_estimation.md
RomanLut Nov 3, 2023
229eac4
Update GPS_fix_estimation.md
RomanLut Nov 3, 2023
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
132 changes: 132 additions & 0 deletions docs/GPS_fix_estimation.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,132 @@
# GPS Fix estimation (dead reconing, RTH without GPS) for fixed wing

Video demonstration

[![IMAGE ALT TEXT HERE](https://img.youtube.com/vi/wzvgRpXCS4U/0.jpg)](https://www.youtube.com/watch?v=wzvgRpXCS4U)

There is possibility to allow plane to estimate it's position when GPS fix is lost.
The main purpose is RTH without GPS.
It works for fixed wing only.

Plane should have the following sensors:
- acceleromenter, gyroscope
- barometer
- GPS
- magnethometer (optional, highly recommended)
- pitot (optional)

By befault, all navigation modes are disabled when GPS fix is lost. If RC signal is lost also, plane will not be able to enable RTH. Plane will switch to LANDING instead. When flying above unreachable spaces, plane will be lost.

GPS fix estimation allows to recover plane using magnetometer and baromener only.

GPS Fix is also estimated on GPS Sensor timeouts (hardware failures).

Note, that GPS fix estimation is not a solution for navigation without GPS. Without GPS fix, position error accumulates quickly. But it is acceptable for RTH. This is not a solution for flying under spoofing also. GPS is the most trusted sensor in Inav. It's output is not validated.

# How it works ?

In normal situation, plane is receiving it's position from GPS sensor. This way it is able to hold course, RTH or navigate by waypoints.

Without GPS fix, plane has nose heading from magnetometer and height from barometer only.

To navigate without GPS fix, we make the following assumptions:
- plane is flying in the direction where nose is pointing
- (if pitot tube is not installed) plane is flying with constant airspeed, specified in settings

It is possible to roughly estimate position using theese assumptions. To increase accuracy, plane will use information about wind direction and speed, estimated before GPS fix was lost. To increase groundspeed estimation accuracy, plane will use pitot tube data(if available).

From estimated heading direction and speed, plane is able to **roughty** estimate it's position.

It is assumed, that plane will fly in roughly estimated direction to home position untill either GPS fix or RC signal is recovered.

*Plane has to aquire GPS fix and store home position before takeoff. Estimation completely without GPS fix will not work*.

# Estimation without magnethometer

Without magnethometer, navigation accuracy is very poor. The problem is heading drift.

The longer plane flies without magnethometer or GPS, the bigger is course estimation error.

After few minutes and few turns, "North" direction estimation can be completely broken.
In general, accuracy is enough to perform RTH U-turn when both RC controls and GPS are lost, and roughtly keep RTH direction in areas with occasional GPS outages.

![image](https://github.com/RomanLut/inav/assets/11955117/3d5c5d10-f43a-45f9-a647-af3cca87c4da)

(purple line - estimated position, black line - real position).

It is recommened to use GPS fix estimation without magnethometer as last resort only. For example, if plane is flying above lake, landing means loss of plane. With GPS Fix estimation, plane will try to do RTH in very rought direction, instead of landing.

It is up to user to estimate the risk of fly-away.


# Settings

GPS Fix estimation is enabled with CLI command:

```set inav_allow_gps_fix_estimation=ON```

Also you have to specify cruise airspeed of the plane.

To find out cruise airspeed, make a test flight. Enable ground speed display on OSD. Flight in CRUISE mode in two opposite directions. Take average speed.

Cruise airspeed is specified in cm/s.

To convert km/h to m/s, multiply by 27.77.


Example: 100 km/h = 100 * 27.77 = 2777 cm/s

```set fw_reference_airspeed=2777```

*It is important, that plane fly with specified speed in CRUISE mode. If you have set option "Increase cruise speed with throttle" - do not use it without GPS Fix.*

*If pitot is available, pitot sensor data will be used instead of constant. It is not necessary to specify fw_reference_airspeed. However, it is still adviced to specify for the case of pitot failure.*

*Note related command: to continue mission without RC signal, see command ```set failsafe_mission_delay=-1```.*

**After entering CLI command, make sure that settings are saved:**

```save```

# Disabling GPS sensor from RC controller

![](Screenshots/programming_disable_gps_sensor_fix.png)

For testing purposes, it is possible to disable GPS sensor fix from RC controller in programming tab:

*GPS can be disabled only after: 1) initial GPS fix is acquired 2) in ARMED mode.*

# Allowing wp missions with GPS Fix estimation

```failsafe_gps_fix_estimation_delay```

Controls whether waypoint mission is allowed to proceed with gps fix estimation. Sets the time delay in seconds between gps fix lost event and RTH activation. Minimum delay is 7 seconds. If set to -1 the mission will continue until the end. With default setting(7), waypoint mission is aborted and switched to RTH with 7 seconds delay. RTH is done with GPS Fix estimation. RTH is trigerred regradless of failsafe procedure selected in configurator.

# Expected error (mag + baro)

Realistic expected error is up to 200m per 1km of flight path. In tests, 500m drift per 5km path was seen.

To dicrease drift:
- fly one large circle with GPS available to get good wind estimation
- use airspeed sensor. If airspeed sensor is not installed, fly in cruise mode without throttle override.
- do smooth, large turns
- make sure compass is pointing in nose direction precicely
- calibrate compass correctly

This video shows real world test where GPS was disabled occasionally. Wind is 10km/h south-west:


https://github.com/RomanLut/inav/assets/11955117/0599a3c3-df06-4d40-a32a-4d8f96140592


Purple line shows estimated position. Black line shows real position. "EST ERR" sensor shows estimation error in metters. Estimation is running when satellite icon displays "ES". Estimated position snaps to real position when GPS fix is reaquired.


# Is it possible to implement this for multirotor ?

There are some ideas, but there is no solution now. We can not make assumptions with multirotor which we can make with a fixed wing.


# Links

INAV HITL https://github.com/RomanLut/INAV-X-Plane-HITL
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
20 changes: 20 additions & 0 deletions docs/Settings.md
Original file line number Diff line number Diff line change
Expand Up @@ -1002,6 +1002,16 @@ Requested yaw rate to execute when `LAND` (or old `SET-THR`) failsafe is active

---

### failsafe_gps_fix_estimation_delay

Controls whether waypoint mission is allowed to proceed with gps fix estimation. Sets the time delay in seconds between gps fix lost event and RTH activation. Minimum delay is 7 seconds. If set to -1 the mission will continue until the end. With default setting(7), waypoint mission is aborted and switched to RTH with 7 seconds delay. RTH is done with GPS Fix estimation.

| Default | Min | Max |
| --- | --- | --- |
| 7 | -1 | 600 |

---

### failsafe_lights

Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF].
Expand Down Expand Up @@ -1762,6 +1772,16 @@ Defines if INAV will dead-reckon over short GPS outages. May also be useful for

---

### inav_allow_gps_fix_estimation

Defines if inav will estimate GPS fix with magnetometer and barometer on GPS outages. Enables navigation and RTH without GPS fix on fixed wing. Also see failsafe_gps_fix_estimation_delay.

| Default | Min | Max |
| --- | --- | --- |
| OFF | OFF | ON |

---

### inav_auto_mag_decl

Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored.
Expand Down
14 changes: 7 additions & 7 deletions src/main/drivers/display.c
Original file line number Diff line number Diff line change
Expand Up @@ -180,13 +180,13 @@ int displayWriteChar(displayPort_t *instance, uint8_t x, uint8_t y, uint16_t c)

#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE_HITL)) {
//some FCs do not power max7456 from USB power
//driver can not read font metadata
//chip assumed to not support second bank of font
//artifical horizon, variometer and home direction are not drawn ( display.c: displayUpdateMaxChar())
//return dummy metadata to let all OSD elements to work in simulator mode
instance->maxChar = 512;
}
//some FCs do not power max7456 from USB power
//driver can not read font metadata
//chip assumed to not support second bank of font
//artifical horizon, variometer and home direction are not drawn ( display.c: displayUpdateMaxChar())
//return dummy metadata to let all OSD elements to work in simulator mode
instance->maxChar = 512;
}
#endif

if (c > instance->maxChar) {
Expand Down
8 changes: 4 additions & 4 deletions src/main/drivers/sound_beeper.c
Original file line number Diff line number Diff line change
Expand Up @@ -48,10 +48,10 @@ void systemBeep(bool onoff)

#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE_HITL)) {
if (SIMULATOR_HAS_OPTION(HITL_MUTE_BEEPER)) {
onoff = false;
}
}
if (SIMULATOR_HAS_OPTION(HITL_MUTE_BEEPER)) {
onoff = false;
}
}
#endif

if (beeperConfig()->pwmMode) {
Expand Down
Loading
Loading