diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index bd1c059ca1..857695bdb9 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -483,7 +483,7 @@ static float current_total1; //////////////////////////////////////////////////////////////////////////////// // Airspeed Sensors //////////////////////////////////////////////////////////////////////////////// -AP_Airspeed airspeed(&pitot_analog_source, AIRSPEED_RATIO, AIRSPEED_SENSOR); +AP_Airspeed airspeed(&pitot_analog_source); //////////////////////////////////////////////////////////////////////////////// // Altitude Sensor variables diff --git a/ArduPlane/config.h b/ArduPlane/config.h index d06528e327..7bfc81fcc1 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -115,18 +115,6 @@ #endif -////////////////////////////////////////////////////////////////////////////// -// AIRSPEED_SENSOR -// AIRSPEED_RATIO -// -#ifndef AIRSPEED_SENSOR -# define AIRSPEED_SENSOR DISABLED -#endif - -#ifndef AIRSPEED_RATIO -# define AIRSPEED_RATIO 1.9936 // Note - this varies from the value in ArduPilot due to the difference in ADC resolution -#endif - ////////////////////////////////////////////////////////////////////////////// // IMU Selection // diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index bc6ad0e310..8def149969 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -38,7 +38,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] PROGMEM = { // @DisplayName: Airspeed ratio // @Description: Airspeed calibration ratio // @Increment: 0.1 - AP_GROUPINFO("RATIO", 3, AP_Airspeed, _ratio, 0), + AP_GROUPINFO("RATIO", 3, AP_Airspeed, _ratio, 1.9936), AP_GROUPEND }; diff --git a/libraries/AP_Airspeed/AP_Airspeed.h b/libraries/AP_Airspeed/AP_Airspeed.h index abb1f8b1a7..75628a216a 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.h +++ b/libraries/AP_Airspeed/AP_Airspeed.h @@ -13,14 +13,8 @@ class AP_Airspeed { public: // constructor - AP_Airspeed(AP_AnalogSource *source, float ratio, bool enable) { + AP_Airspeed(AP_AnalogSource *source) { _source = source; - _offset.set(0); - _ratio.set(ratio); - - // by default enable but don't use the airspeed sensor - _use.set(1); - _enable.set(enable?1:0); } // read the analog source and update _airspeed