AP_AHRS: Added get_max_wind to make it available for use in determining if the airspeed sensor is faulty.

This commit is contained in:
ChrisBird 2019-01-14 04:39:53 -08:00 committed by Tom Pittenger
parent 5dbf603450
commit 532431c284

View File

@ -304,6 +304,11 @@ public:
return _airspeed != nullptr && _airspeed->use() && _airspeed->healthy();
}
// return the parameter AHRS_WIND_MAX in metres per second
uint8_t get_max_wind() const {
return _wind_max;
}
// return a ground vector estimate in meters/second, in North/East order
virtual Vector2f groundspeed_vector(void);