diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index 3ccab8a7c4..d63d881ab9 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -1185,7 +1185,7 @@ void AC_PosControl::check_for_ekf_z_reset() // check for position shift float alt_shift; uint32_t reset_ms = _ahrs.getLastPosDownReset(alt_shift); - if (reset_ms != _ekf_z_reset_ms) { + if (reset_ms != 0 && reset_ms != _ekf_z_reset_ms) { shift_alt_target(-alt_shift * 100.0f); _ekf_z_reset_ms = reset_ms; }