diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index a29a2e3e17..8634266840 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -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