From 001d18b51dea80beb5022225121f3f7280ccbe95 Mon Sep 17 00:00:00 2001
From: Andrew Tridgell <tridge@samba.org>
Date: Mon, 13 May 2013 15:15:16 +1000
Subject: [PATCH] Plane: removed scaling of pitot source

---
 ArduPlane/ArduPlane.pde | 5 +++--
 ArduPlane/config.h      | 5 -----
 ArduPlane/test.pde      | 4 ++--
 3 files changed, 5 insertions(+), 9 deletions(-)

diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde
index 5639330f7..f1fc7ba24 100644
--- a/ArduPlane/ArduPlane.pde
+++ b/ArduPlane/ArduPlane.pde
@@ -665,9 +665,10 @@ void setup() {
 
 #if CONFIG_PITOT_SOURCE == PITOT_SOURCE_ADC
     pitot_analog_source = new AP_ADC_AnalogSource( &adc,
-                                         CONFIG_PITOT_SOURCE_ADC_CHANNEL, 1.0);
+                                         CONFIG_PITOT_SOURCE_ADC_CHANNEL, 1.0f);
 #elif CONFIG_PITOT_SOURCE == PITOT_SOURCE_ANALOG_PIN
-    pitot_analog_source = hal.analogin->channel(CONFIG_PITOT_SOURCE_ANALOG_PIN, CONFIG_PITOT_SCALING);
+    pitot_analog_source = hal.analogin->channel(CONFIG_PITOT_SOURCE_ANALOG_PIN);
+    hal.gpio->write(hal.gpio->analogPinToDigitalPin(CONFIG_PITOT_SOURCE_ANALOG_PIN), 0);
 #endif
     vcc_pin = hal.analogin->channel(ANALOG_INPUT_BOARD_VCC);
 
diff --git a/ArduPlane/config.h b/ArduPlane/config.h
index 646ac15e3..52292075c 100644
--- a/ArduPlane/config.h
+++ b/ArduPlane/config.h
@@ -118,7 +118,6 @@
  # define CONFIG_INS_TYPE CONFIG_INS_MPU6000
  # define CONFIG_PITOT_SOURCE PITOT_SOURCE_ANALOG_PIN
  # define CONFIG_PITOT_SOURCE_ANALOG_PIN 0
- # define CONFIG_PITOT_SCALING 4.0
  # ifdef APM2_BETA_HARDWARE
  #  define CONFIG_BARO     AP_BARO_BMP085
  # else // APM2 Production Hardware (default)
@@ -137,7 +136,6 @@
  # define CONFIG_INS_TYPE CONFIG_INS_STUB
  # define CONFIG_PITOT_SOURCE PITOT_SOURCE_ANALOG_PIN
  # define CONFIG_PITOT_SOURCE_ANALOG_PIN 0
- # define CONFIG_PITOT_SCALING 4.0
  # define CONFIG_BARO     AP_BARO_HIL
  # define CONFIG_COMPASS  AP_COMPASS_HIL
 #elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
@@ -152,7 +150,6 @@
  # define CONFIG_INS_TYPE CONFIG_INS_PX4
  # define CONFIG_PITOT_SOURCE PITOT_SOURCE_ANALOG_PIN
  # define CONFIG_PITOT_SOURCE_ANALOG_PIN 11
- # define CONFIG_PITOT_SCALING (4.0*5.0/3.3)
  # define CONFIG_BARO AP_BARO_PX4
  # define CONFIG_COMPASS  AP_COMPASS_PX4
  # define SERIAL0_BAUD 115200
@@ -202,8 +199,6 @@
  #define CONFIG_PITOT_SOURCE PITOT_SOURCE_ANALOG_PIN
  #undef CONFIG_PITOT_SOURCE_ANALOG_PIN
  #define CONFIG_PITOT_SOURCE_ANALOG_PIN -1
- #undef CONFIG_PITOT_SCALING
- #define CONFIG_PITOT_SCALING 4.0
  #undef  CONFIG_COMPASS
  #define CONFIG_COMPASS  AP_COMPASS_HIL
 #endif
diff --git a/ArduPlane/test.pde b/ArduPlane/test.pde
index e594db3f5..f22e12322 100644
--- a/ArduPlane/test.pde
+++ b/ArduPlane/test.pde
@@ -606,9 +606,9 @@ test_mag(uint8_t argc, const Menu::arg *argv)
 static int8_t
 test_airspeed(uint8_t argc, const Menu::arg *argv)
 {
-    float airspeed_ch = pitot_analog_source->read_average();
+    float airspeed_ch = pitot_analog_source->voltage_average();
     // cliSerial->println(pitot_analog_source.read());
-    cliSerial->printf_P(PSTR("airspeed_ch: %.1f\n"), airspeed_ch);
+    cliSerial->printf_P(PSTR("airspeed_ch: %.3f\n"), airspeed_ch);
 
     if (!airspeed.enabled()) {
         cliSerial->printf_P(PSTR("airspeed: "));
-- 
GitLab