AP_AHRS: use EKF for groundspeed estimate if available
This commit is contained in:
parent
2815af81ad
commit
a6cbc5d4a5
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user