diff --git a/libraries/AP_InertialNav/AP_InertialNav.cpp b/libraries/AP_InertialNav/AP_InertialNav.cpp index 332a439be4..704a2ea568 100644 --- a/libraries/AP_InertialNav/AP_InertialNav.cpp +++ b/libraries/AP_InertialNav/AP_InertialNav.cpp @@ -351,6 +351,7 @@ void AP_InertialNav::set_altitude( float new_altitude) _position_base.z = new_altitude; _position_correction.z = 0; _position.z = new_altitude; // _position = _position_base + _position_correction + _hist_position_estimate_z.clear(); // reset z history to avoid fake z velocity at next baro calibration (next rearm) } //