From a6cbc5d4a59c1391ae782fef24cdcff04a3f39d2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 31 May 2016 15:55:41 +1000 Subject: [PATCH] AP_AHRS: use EKF for groundspeed estimate if available --- libraries/AP_AHRS/AP_AHRS.h | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 4e2d49ab1c..099924d04f 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -294,11 +294,8 @@ public: } // return ground speed estimate in meters/second. Used by ground vehicles. - float groundspeed(void) const { - if (_gps.status() <= AP_GPS::NO_FIX) { - return 0.0f; - } - return _gps.ground_speed(); + float groundspeed(void) { + return groundspeed_vector().length(); } // return true if we will use compass for yaw