AHRS: enable barometer for vertical velocity

this re-enables the barometer for vertical velocity information
for drift correction, now that we have a better filter
on the climb rate
This commit is contained in:
Andrew Tridgell 2012-07-05 08:10:59 +10:00
parent a5d607d25a
commit 6653c0b874

View File

@ -411,7 +411,7 @@ AP_AHRS_DCM::drift_correction(float deltat)
_have_gps_lock = true;
}
#if 0
#if 1
/*
NOTE: The barometric vertical acceleration correction is disabled
until we work out how to filter it sufficiently to be usable