AP_AHRS: added groundspeed() method

this gives ground speed in m/s from GPS
This commit is contained in:
Andrew Tridgell 2013-09-09 10:17:45 +10:00
parent 0918393fed
commit c044385fff
1 changed files with 8 additions and 0 deletions

View File

@ -191,6 +191,14 @@ public:
// return a ground vector estimate in meters/second, in North/East order
Vector2f groundspeed_vector(void);
// return ground speed estimate in meters/second. Used by ground vehicles.
float groundspeed(void) const {
if (!_gps || _gps->status() <= GPS::NO_FIX) {
return 0.0f;
}
return _gps->ground_speed_cm * 0.01f;
}
// return true if we will use compass for yaw
virtual bool use_compass(void) const { return _compass && _compass->use_for_yaw(); }