Skip to content

Commit 91423d4

Browse files
priseboroughpeterbarker
authored andcommitted
AP_NavEKF3: Remove unncessary local position height reporting offset
The offset generated by the EK3_OGN_HGT_MASK parameter bit 2 option is applied to the baro or range finder sensor so it does not have to be applied to the local position height.
1 parent 5fded75 commit 91423d4

File tree

1 file changed

+1
-11
lines changed

1 file changed

+1
-11
lines changed

libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp

Lines changed: 1 addition & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -260,17 +260,7 @@ bool NavEKF3_core::getPosNE(Vector2f &posNE) const
260260
// Return true if the estimate is valid
261261
bool NavEKF3_core::getPosD_local(float &posD) const
262262
{
263-
// The EKF always has a height estimate regardless of mode of operation
264-
// Correct for the IMU offset (EKF calculations are at the IMU)
265-
// Also correct for changes to the origin height
266-
if ((frontend->_originHgtMode & (1<<2)) == 0) {
267-
// Any sensor height drift corrections relative to the WGS-84 reference are applied to the origin.
268-
posD = outputDataNew.position.z + posOffsetNED.z;
269-
} else {
270-
// The origin height is static and corrections are applied to the local vertical position
271-
// so that height returned by getLLH() = height returned by getOriginLLH - posD
272-
posD = outputDataNew.position.z + posOffsetNED.z + 0.01f * (float)EKF_origin.alt - (float)ekfGpsRefHgt;
273-
}
263+
posD = outputDataNew.position.z + posOffsetNED.z;
274264

275265
// Return the current height solution status
276266
return filterStatus.flags.vert_pos;

0 commit comments

Comments
 (0)