Skip to content

Commit 04f24e7

Browse files
committed
AP_NavEKF3: always apply ekfGpsRefHgt corrections
Co-authored-by: Pavlo Kolomiiets <[email protected]> ArduPilot#24039 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.
1 parent 00bf485 commit 04f24e7

File tree

1 file changed

+1
-5
lines changed

1 file changed

+1
-5
lines changed

libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp

Lines changed: 1 addition & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -684,11 +684,7 @@ void NavEKF3_core::readGpsData()
684684
if (validOrigin) {
685685
gpsDataNew.lat = gpsloc.lat;
686686
gpsDataNew.lng = gpsloc.lng;
687-
if ((frontend->_originHgtMode & (1<<2)) == 0) {
688-
gpsDataNew.hgt = (ftype)((double)0.01 * (double)gpsloc.alt - ekfGpsRefHgt);
689-
} else {
690-
gpsDataNew.hgt = 0.01 * (gpsloc.alt - EKF_origin.alt);
691-
}
687+
gpsDataNew.hgt = (ftype)((double)0.01 * (double)gpsloc.alt - ekfGpsRefHgt);
692688
storedGPS.push(gpsDataNew);
693689
// declare GPS in use
694690
gpsIsInUse = true;

0 commit comments

Comments
 (0)