AP_NavEKF3: Adjust sensor height when EK3_OGN_HGT_MASK bit 2 is set

This commit is contained in:
Paul Riseborough 2024-05-21 20:26:26 +10:00 committed by Randy Mackay
parent dbcd089b44
commit 7b6644c2cf
2 changed files with 11 additions and 0 deletions

View File

@ -685,8 +685,10 @@ void NavEKF3_core::readGpsData()
gpsDataNew.lat = gpsloc.lat;
gpsDataNew.lng = gpsloc.lng;
if ((frontend->_originHgtMode & (1<<2)) == 0) {
// the height adjustment to match GPS is being achieved by adjusting the origin height
gpsDataNew.hgt = (ftype)((double)0.01 * (double)gpsloc.alt - ekfGpsRefHgt);
} else {
// the height adjustment to match GPS is being achieved by adjusting the measurements
gpsDataNew.hgt = 0.01 * (gpsloc.alt - EKF_origin.alt);
}
storedGPS.push(gpsDataNew);

View File

@ -1273,6 +1273,11 @@ void NavEKF3_core::selectHeightForFusion()
hgtMea = MAX(rangeDataDelayed.rng * prevTnb.c.z, rngOnGnd);
// correct for terrain position relative to datum
hgtMea -= terrainState;
// correct sensor so that local position height adjusts to match GPS
if (frontend->_originHgtMode & (1 << 1) && frontend->_originHgtMode & (1 << 2)) {
// offset has to be applied to the measurement, not the NED origin
hgtMea += (float)(ekfGpsRefHgt - 0.01 * (double)EKF_origin.alt);
}
velPosObs[5] = -hgtMea;
// enable fusion
fuseHgtData = true;
@ -1299,6 +1304,10 @@ void NavEKF3_core::selectHeightForFusion()
} else if (baroDataToFuse && (activeHgtSource == AP_NavEKF_Source::SourceZ::BARO)) {
// using Baro data
hgtMea = baroDataDelayed.hgt - baroHgtOffset;
// correct sensor so that local position height adjusts to match GPS
if (frontend->_originHgtMode & (1 << 0) && frontend->_originHgtMode & (1 << 2)) {
hgtMea += (float)(ekfGpsRefHgt - 0.01 * (double)EKF_origin.alt);
}
// enable fusion
fuseHgtData = true;
// set the observation noise