AP_Airspeed: fix for AnalogIn read_average

This commit is contained in:
Pat Hickey 2012-12-06 15:58:40 -08:00 committed by Andrew Tridgell
parent 8f99a12374
commit 7017a35fc3
2 changed files with 5 additions and 8 deletions

View File

@ -8,8 +8,7 @@
* of the License, or (at your option) any later version. * of the License, or (at your option) any later version.
*/ */
#include <math.h> #include <AP_Math.h>
#include <AP_Common.h> #include <AP_Common.h>
#include <AP_HAL.h> #include <AP_HAL.h>
#include <AP_Airspeed.h> #include <AP_Airspeed.h>
@ -55,10 +54,10 @@ void AP_Airspeed::calibrate()
if (!_enable) { if (!_enable) {
return; return;
} }
_source->read(); _source->read_average();
for (c = 0; c < 10; c++) { for (c = 0; c < 10; c++) {
hal.scheduler->delay(100); hal.scheduler->delay(100);
sum += _source->read(); sum += _source->read_average();
} }
_airspeed_raw = sum/c; _airspeed_raw = sum/c;
_offset.set_and_save(_airspeed_raw); _offset.set_and_save(_airspeed_raw);
@ -72,9 +71,8 @@ void AP_Airspeed::read(void)
if (!_enable) { if (!_enable) {
return; return;
} }
_airspeed_raw = _source->read(); _airspeed_raw = _source->read_average();
airspeed_pressure = ((_airspeed_raw - _offset) < 0) ? airspeed_pressure = max(_airspeed_raw - _offset, 0);
(_airspeed_raw - _offset) : 0;
_airspeed = 0.7 * _airspeed + _airspeed = 0.7 * _airspeed +
0.3 * sqrt(airspeed_pressure * _ratio); 0.3 * sqrt(airspeed_pressure * _ratio);
} }

View File

@ -21,7 +21,6 @@ public:
// calibrate the airspeed. This must be called on startup if the // calibrate the airspeed. This must be called on startup if the
// altitude/climb_rate/acceleration interfaces are ever used // altitude/climb_rate/acceleration interfaces are ever used
// the callback is a delay() like routine
void calibrate(); void calibrate();
// return the current airspeed in m/s // return the current airspeed in m/s