From b7350118a6ee19265adb79eee6a6eb4723fff5a5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 13 Apr 2014 19:42:49 +1000 Subject: [PATCH] AP_AHRS: enable EKF wind estimate with no airspeed sensor EKF can now estimate with IMU and GPS only Pair-Programmed-With: Paul Riseborough --- libraries/AP_AHRS/AP_AHRS_NavEKF.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp index cb19b212b3..3bd7d5793b 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp @@ -122,7 +122,7 @@ float AP_AHRS_NavEKF::get_error_yaw(void) // return a wind estimation vector, in m/s Vector3f AP_AHRS_NavEKF::wind_estimate(void) { - if (!using_EKF() || !_airspeed || !_airspeed->use()) { + if (!using_EKF()) { // EKF does not estimate wind speed when there is no airspeed // sensor active return AP_AHRS_DCM::wind_estimate();