Browse Source

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

mission-4.1.18
Ju1ien 11 years ago committed by Randy Mackay
parent
commit
28ce66f314
  1. 1
      libraries/AP_InertialNav/AP_InertialNav.cpp

1
libraries/AP_InertialNav/AP_InertialNav.cpp

@ -351,6 +351,7 @@ void AP_InertialNav::set_altitude( float new_altitude) @@ -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)
}
//

Loading…
Cancel
Save