By default EKF3 uses barometer for altitude estimation. Which is controlled by this parameters:
"EK3_SRC1_POSZ": 1, #1 - baro
"EK3_SRC2_POSZ": 1,
"EK3_SRC3_POSZ": 1
I am trying to use GPS as optional altitude source to have a protection against barometer errors.
"EK3_SRC2_POSZ": 3 # 3 - GPS
I use SITL + autotest.py
to simulate barometer errors.
Gradually increase baro error over time:
self.set_parameters({"SIM_BARO_GLITCH": deltaTime * 2}, verbose=False)
And plane in SITL successfully crashed every time. There is no EKF line switches.
I also tried to use EK3_OGN_HGT_MASK
parameter. But I don’t see any effect.
I want to stay with barometer as a primary source for altitude (POSZ).
But use GPS as an alternative source to correct barometer errors.
How can I achieve that with EKF3?
Just in case if someone interested.
Parameter EK3_OGN_HGT_MASK
doesn’t work as expected until this bug fix:
opened 01:17PM - 12 Jun 23 UTC
closed 12:36AM - 23 May 24 UTC
BUG
EKF
## Bug report
**Issue details**
If 3rd bit of `EK3_OGN_HGT_MASK` is set to… gether with 1st bit (EK3_OGN_HGT_MASK=5) and vertical position is taken from barometr (default parameters), copter climbs periodically indefinitely. The plot below shows 10x SITL simulation with real altitude (barometer or gps) jumping at regular intervals, while the controller (and EKF) altitude remaining constant. The real alt increases as copter periodically thinks it's below desired altitude (100m) and simply turns on the throttle to keep it.
![alt](https://github.com/ArduPilot/ardupilot/assets/27725335/5ffef0ee-26b1-4998-8d79-1557df87edcc)
The reason is in `readGpsData` here
https://github.com/ArduPilot/ardupilot/blob/514434193d7c4dba259180db4a9aa83391c7cf01/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp#L693
When 3rd bit is set, Ardupilot doesn't use `ekfGpsRefHgt` to convert GPS alt to local alt. But it still updates `ekfGpsRefHgt` in `correctEkfOriginHeight`. And the innovation used in the latter is constantly non-zero.
The jumps in alt are introduced by the 5-sigma check here. If the check is removed, the alt rises smoothly and with acceleration.
https://github.com/ArduPilot/ardupilot/blob/514434193d7c4dba259180db4a9aa83391c7cf01/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp#L817
It seems the cure is to always use `ekfGpsRefHgt` to convert GPS alt to local alt in `readGpsData`. Tested and it worked ok.
**Version**
Copter-4.3.7
**Platform**
[ ] All
[ ] AntennaTracker
[*] Copter
[ ] Plane
[ ] Rover
[ ] Submarine
**Airframe type**
octa
**Hardware type**
SITL
**Logs**
[BIN log](https://drive.google.com/file/d/1L9tBvGNUPdPz3cMmc6Q-fqI0JJzFv-RY/view?usp=sharing)
I tried SITL with Plane-4.4 and Plane-4.5. EK3_OGN_HGT_MASK
parameter doesn’t help with baro drift at all.
From master branch (25 Jun 2024). This pull request is merged: Fix infinite climb bug when using EK3_OGN_HGT_MASK by peterbarker · Pull Request #26917 · ArduPilot/ardupilot · GitHub
EK3_OGN_HGT_MASK, 5
does help with SLOW baro drifts:
self.set_parameters({"SIM_BARO_GLITCH": deltaTime * 0.1}, verbose=False)
Ardupilot corrects Altitude by GPS data.
For sudden simulated baro glitches EK3_OGN_HGT_MASK, 5
doesn’t help. Altitude is not corrected at all. Even from master branch with this fix: Fix infinite climb bug when using EK3_OGN_HGT_MASK by peterbarker · Pull Request #26917 · ArduPilot/ardupilot · GitHub
1 Like
rmackay9
(rmackay9)
June 25, 2024, 11:38pm
3
Hi @postelzhuk ,
Thanks for the testing and feedback.
So my understanding is that you’re pretty sure that if the EKF is setup to use barometer with slow corrections from the GPS this doesn’t work in 4.5.x but it does work in master?
I’ve added this to the 4.5 issues list so we will discuss it at the next dev call.
Hi @rmackay9 ,
Thanks for reply.
I just double checked this behavior in Plane-4.5
branch.
Here is some details about my autotests:
I use SIM_BARO_GLITCH
parameter to simulate barometer errors. Here is the code example:
baroGlitch = deltaTime * 0.1
if baroGlitch > 50.0:
baroGlitch = 50.0
self._autoTest.set_parameters({"SIM_BARO_GLITCH": baroGlitch}, verbose=False)
For Altitude check I compare data from SIM_STATE
and GLOBAL_POSITION_INT
messages.
On the start of the test I set this parameters: "EK3_SRC1_POSZ": 1
and "EK3_OGN_HGT_MASK": 5
and reboot sitl
Without fix (Fix infinite climb bug when using EK3_OGN_HGT_MASK by peterbarker · Pull Request #26917 · ArduPilot/ardupilot · GitHub ) altitude difference between SIM_STATE altitude and GLOBAL_POSITION_INT altitude is always approximately the same as SIM_BARO_GLITCH value. Some log examples:
AT-0015.4: Waiting for WGBarometerTest (98.40/720.00)
AT-0015.5: Sim: lat=-35.330874,lon=149.156954,alt=670.7, Global: lat=-35.330835,lon=149.156934,alt=682.1
AT-0015.5: Delta: 4.71, simRelativeAlt: 85.68, altDelta: -11.34
AT-0015.5: set_parameters: ({'SIM_BARO_GLITCH': 9.840000000000002})
AT-0070.1: Waiting for WGBarometerTest (705.20/720.00)
AT-0070.2: Sim: lat=-35.344528,lon=149.154138,alt=632.3, Global: lat=-35.344549,lon=149.154146,alt=684.9
AT-0070.2: Delta: 2.45, simRelativeAlt: 47.23, altDelta: -52.64
AT-0070.2: set_parameters: ({'SIM_BARO_GLITCH': 50.0})
From master branch (with fix) EK3_OGN_HGT_MASK": 5
helps to avoid altitude delta between SIM_STATE and GLOBAL_POSITION_INT. Ardupilot corrects the altitude with GPS data. But ONLY with a slow baro glitches (baroGlitch = deltaTime * 0.1
)
If I set baroGlitch to increase more quickly (baroGlitch = deltaTime * 0.2
). EK3_OGN_HGT_MASK": 5
doesn’t help to correct the barometer error completely.
Pashek
(Pashek)
July 30, 2024, 11:44am
5
Most probable reason is that with sudden baro glitches, EKF stops correcting baro altitude bcz of the 5-sigma check here . If it’s just a glitch and not a permanent baro drift that is too fast, then EKF will resume the correction eventually, after the altitude covariance grows high enough.
Pashek
(Pashek)
July 30, 2024, 12:10pm
7
For sudden simulated baro glitches EK3_OGN_HGT_MASK, 5
doesn’t help. Altitude is not corrected at all. Even from master branch with this fix: Fix infinite climb bug when using EK3_OGN_HGT_MASK by peterbarker · Pull Request #26917 · ArduPilot/ardupilot · GitHub
From this I understood that for sudden baro glitches even master with PR doesn’t help. Am I wrong?
@Pashek If you are talking about this point then yes. The reason why EKF stops correcting faster baro glitches is exactly in this line of code. I debuged this with GDB.