From 7f46cc90592d99e6e34f01d8a5f81d49e06f5a51 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 1 Aug 2015 17:37:59 +0900 Subject: [PATCH] AHRS_DCM: integrate INS use_accel --- libraries/AP_AHRS/AP_AHRS_DCM.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index 432bda539e..f4069a0648 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -571,7 +571,7 @@ AP_AHRS_DCM::drift_correction(float deltat) //update _accel_ef_blended #if HAL_CPU_CLASS >= HAL_CPU_CLASS_75 - if (_ins.get_accel_count() == 2 && _ins.get_accel_health(0) && _ins.get_accel_health(1)) { + if (_ins.get_accel_count() == 2 && _ins.use_accel(0) && _ins.use_accel(1)) { float imu1_weight_target = _active_accel_instance == 0 ? 1.0f : 0.0f; // slew _imu1_weight over one second _imu1_weight += constrain_float(imu1_weight_target-_imu1_weight, -deltat, deltat);