AP_Airspeed: removed values passed to constructor

This commit is contained in:
Andrew Tridgell 2012-08-08 16:36:41 +10:00
parent e6e25525bc
commit dcc50b5705
4 changed files with 3 additions and 21 deletions

View File

@ -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

View File

@ -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
//

View File

@ -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
};

View File

@ -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