AP_Airspeed: added get_airspeed_ratio() and set_airspeed_ratio()

This is to help Paul develop an automatic tuning system for airspeed
ratio
This commit is contained in:
Andrew Tridgell 2013-07-13 21:53:38 +10:00
parent d4db2231d4
commit 9d66adae13
1 changed files with 15 additions and 5 deletions

View File

@ -25,27 +25,37 @@ public:
void calibrate();
// return the current airspeed in m/s
float get_airspeed(void) {
float get_airspeed(void) const {
return _airspeed;
}
// return the unfiltered airspeed in m/s
float get_raw_airspeed(void) {
float get_raw_airspeed(void) const {
return _raw_airspeed;
}
// return the current airspeed in cm/s
float get_airspeed_cm(void) {
float get_airspeed_cm(void) const {
return _airspeed*100;
}
// return the current airspeed ratio (dimensionless)
float get_airspeed_ratio(void) const {
return _ratio;
}
// set the airspeed ratio (dimensionless)
void set_airspeed_ratio(float ratio) {
_ratio.set(ratio);
}
// return true if airspeed is enabled, and airspeed use is set
bool use(void) {
bool use(void) const {
return _enable && _use && _offset != 0;
}
// return true if airspeed is enabled
bool enabled(void) {
bool enabled(void) const {
return _enable;
}