INav: clear historic z-axis position estimate when set_altitude called

This commit is contained in:
Ju1ien 2014-06-06 18:10:55 +09:00 committed by Randy Mackay
parent abd1370b2c
commit 28ce66f314
1 changed files with 1 additions and 0 deletions

View File

@ -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)
}
//