Skip to content

Commit

Permalink
AP_NavEKF3: Adjust sensor height when EK3_OGN_HGT_MASK bit 2 is set
Browse files Browse the repository at this point in the history
  • Loading branch information
priseborough authored and peterbarker committed May 22, 2024
1 parent 2beb3db commit d7ebe82
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 0 deletions.
2 changes: 2 additions & 0 deletions libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
9 changes: 9 additions & 0 deletions libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1278,6 +1278,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;
Expand All @@ -1304,6 +1309,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
Expand Down

0 comments on commit d7ebe82

Please sign in to comment.