From 011110e1dd0753e857e2e543d6f15cfa82b16c4b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 10 Dec 2011 21:45:34 +1100 Subject: [PATCH] airspeed: use floating point values and better averaging in zero_airspeed() this makes the calibration of airspeed a bit more accurate, and prevents truncation of airspeed values --- ArduCopter/test.pde | 2 +- ArduPlane/ArduPlane.pde | 2 +- ArduPlane/sensors.pde | 19 +++++++++++-------- ArduPlane/test.pde | 8 ++++---- 4 files changed, 17 insertions(+), 14 deletions(-) diff --git a/ArduCopter/test.pde b/ArduCopter/test.pde index 3693c289cb..50a7495b7d 100644 --- a/ArduCopter/test.pde +++ b/ArduCopter/test.pde @@ -422,7 +422,7 @@ test_radio(uint8_t argc, const Menu::arg *argv) while(1){ for(int i = 0; i < 9; i++){ - Serial.printf_P(PSTR("%u,"),adc.Ch(i)); + Serial.printf_P(PSTR("%.1f,"),adc.Ch(i)); } Serial.println(); delay(20); diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 18e8b72349..0a4c5d88a5 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -364,7 +364,7 @@ static float current_total; // Airspeed Sensors // ---------------- static float airspeed_raw; // Airspeed Sensor - is a float to better handle filtering -static int airspeed_pressure; // airspeed as a pressure value +static float airspeed_pressure; // airspeed as a pressure value // Barometer Sensor variables // -------------------------- diff --git a/ArduPlane/sensors.pde b/ArduPlane/sensors.pde index 9dbfe17175..078761c193 100644 --- a/ArduPlane/sensors.pde +++ b/ArduPlane/sensors.pde @@ -80,9 +80,9 @@ static void read_airspeed(void) airspeed_raw = (float)adc.Ch(AIRSPEED_CH); g.airspeed_offset.set_and_save(airspeed_raw); } - airspeed_raw = ((float)adc.Ch(AIRSPEED_CH) * .25) + (airspeed_raw * .75); - airspeed_pressure = max(((int)airspeed_raw - g.airspeed_offset), 0); - airspeed = sqrt((float)airspeed_pressure * g.airspeed_ratio) * 100; + airspeed_raw = (adc.Ch(AIRSPEED_CH) * 0.25) + (airspeed_raw * 0.75); + airspeed_pressure = max((airspeed_raw - g.airspeed_offset), 0); + airspeed = sqrt(airspeed_pressure * g.airspeed_ratio) * 100; #endif calc_airspeed_errors(); @@ -90,12 +90,15 @@ static void read_airspeed(void) static void zero_airspeed(void) { - airspeed_raw = (float)adc.Ch(AIRSPEED_CH); - for(int c = 0; c < 10; c++){ - delay(20); - airspeed_raw = (airspeed_raw * .90) + ((float)adc.Ch(AIRSPEED_CH) * .10); + float sum = 0; + int c; + airspeed_raw = adc.Ch(AIRSPEED_CH); + for(c = 0; c < 250; c++) { + delay(2); + sum += adc.Ch(AIRSPEED_CH); } - g.airspeed_offset.set_and_save(airspeed_raw); + sum /= c; + g.airspeed_offset.set_and_save((int16_t)sum); } #endif // HIL_MODE != HIL_MODE_ATTITUDE diff --git a/ArduPlane/test.pde b/ArduPlane/test.pde index 0039ce3956..4757a4e1c3 100644 --- a/ArduPlane/test.pde +++ b/ArduPlane/test.pde @@ -459,7 +459,7 @@ test_adc(uint8_t argc, const Menu::arg *argv) delay(1000); while(1){ - for (int i=0;i<9;i++) Serial.printf_P(PSTR("%u\t"),adc.Ch(i)); + for (int i=0;i<9;i++) Serial.printf_P(PSTR("%.1f\t"),adc.Ch(i)); Serial.println(); delay(100); if(Serial.available() > 0){ @@ -630,9 +630,9 @@ test_mag(uint8_t argc, const Menu::arg *argv) static int8_t test_airspeed(uint8_t argc, const Menu::arg *argv) { - unsigned airspeed_ch = adc.Ch(AIRSPEED_CH); + float airspeed_ch = adc.Ch(AIRSPEED_CH); // Serial.println(adc.Ch(AIRSPEED_CH)); - Serial.printf_P(PSTR("airspeed_ch: %u\n"), airspeed_ch); + Serial.printf_P(PSTR("airspeed_ch: %.1f\n"), airspeed_ch); if (g.airspeed_enabled == false){ Serial.printf_P(PSTR("airspeed: ")); @@ -648,7 +648,7 @@ test_airspeed(uint8_t argc, const Menu::arg *argv) while(1){ delay(20); read_airspeed(); - Serial.printf_P(PSTR("%fm/s\n"), airspeed / 100.0); + Serial.printf_P(PSTR("%.1f m/s\n"), airspeed / 100.0); if(Serial.available() > 0){ return (0);