AP_AHRS: enable EKF wind estimate with no airspeed sensor

EKF can now estimate with IMU and GPS only

Pair-Programmed-With: Paul Riseborough <p_riseborough@live.com.au>
This commit is contained in:
Andrew Tridgell 2014-04-13 19:42:49 +10:00
parent 4abc2999a6
commit b7350118a6

View File

@ -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();