AHRS: only enable barometer for AHRS if it is smooth enough

if we used less than 5 samples to compute the pressure then don't use
it for climb rate
This commit is contained in:
Andrew Tridgell 2012-07-05 16:28:29 +10:00
parent 1ce4a03147
commit e33554a1f9

View File

@ -411,17 +411,15 @@ AP_AHRS_DCM::drift_correction(float deltat)
_have_gps_lock = true; _have_gps_lock = true;
} }
#if 1
/* /*
NOTE: The barometric vertical acceleration correction is disabled The barometer for vertical velocity is only enabled if we got
until we work out how to filter it sufficiently to be usable at least 5 pressure samples for the reading. This ensures we
on ArduCopter don't use very noisy climb rate data
*/ */
if (_barometer != NULL) { if (_barometer != NULL && _barometer->get_pressure_samples() >= 5) {
// Z velocity is down // Z velocity is down
velocity.z = - _barometer->get_climb_rate(); velocity.z = - _barometer->get_climb_rate();
} }
#endif
// see if this is our first time through - in which case we // see if this is our first time through - in which case we
// just setup the start times and return // just setup the start times and return