fixed airspeed sensor for ArduPlane on APM2

we were trying to use a non-existant ADC chip!
This commit is contained in:
Andrew Tridgell 2011-12-17 07:19:03 +11:00
parent 7c939e83e0
commit 5d2301ef47
5 changed files with 13 additions and 8 deletions

View File

@ -131,7 +131,9 @@ static AP_Int8 *flight_modes = &g.flight_mode1;
#if HIL_MODE == HIL_MODE_DISABLED
// real sensors
#if CONFIG_ADC == ENABLED
static AP_ADC_ADS7844 adc;
#endif
#ifdef DESKTOP_BUILD
AP_Baro_BMP085_HIL barometer;
@ -224,9 +226,9 @@ ModeFilter sonar_mode_filter;
#if CONFIG_PITOT_SOURCE == PITOT_SOURCE_ADC
AP_AnalogSource_ADC pitot_analog_source( &adc,
CONFIG_PITOT_SOURCE_ADC_CHANNEL, 0.25);
CONFIG_PITOT_SOURCE_ADC_CHANNEL, 1.0);
#elif CONFIG_PITOT_SOURCE == PITOT_SOURCE_ANALOG_PIN
AP_AnalogSource_Arduino pitot_analog_source(CONFIG_PITOT_SOURCE_ANALOG_PIN);
AP_AnalogSource_Arduino pitot_analog_source(CONFIG_PITOT_SOURCE_ANALOG_PIN, 4.0);
#endif
#if SONAR_TYPE == MAX_SONAR_XL

View File

@ -65,6 +65,7 @@
# define CONFIG_RELAY DISABLED
# define MAG_ORIENTATION AP_COMPASS_APM2_SHIELD
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define CONFIG_PITOT_SOURCE PITOT_SOURCE_ANALOG_PIN
# ifdef APM2_BETA_HARDWARE
# define CONFIG_BARO AP_BARO_BMP085
# else // APM2 Production Hardware (default)

View File

@ -77,10 +77,10 @@ static void read_airspeed(void)
// calibration before we can use it. This isn't as
// accurate as the 50 point average in zero_airspeed(),
// but it is better than using it uncalibrated
airspeed_raw = (float)adc.Ch(AIRSPEED_CH);
airspeed_raw = pitot_analog_source.read();
g.airspeed_offset.set_and_save(airspeed_raw);
}
airspeed_raw = (adc.Ch(AIRSPEED_CH) * 0.1) + (airspeed_raw * 0.9);
airspeed_raw = (pitot_analog_source.read() * 0.1) + (airspeed_raw * 0.9);
airspeed_pressure = max((airspeed_raw - g.airspeed_offset), 0);
airspeed = sqrt(airspeed_pressure * g.airspeed_ratio) * 100;
#endif
@ -92,10 +92,10 @@ static void zero_airspeed(void)
{
float sum = 0;
int c;
airspeed_raw = adc.Ch(AIRSPEED_CH);
airspeed_raw = pitot_analog_source.read();
for(c = 0; c < 250; c++) {
delay(2);
sum += adc.Ch(AIRSPEED_CH);
sum += pitot_analog_source.read();
}
sum /= c;
g.airspeed_offset.set_and_save((int16_t)sum);

View File

@ -177,7 +177,9 @@ static void init_ardupilot()
#if HIL_MODE != HIL_MODE_ATTITUDE
#if CONFIG_ADC == ENABLED
adc.Init(&timer_scheduler); // APM ADC library initialization
#endif
barometer.init(&timer_scheduler);

View File

@ -626,8 +626,8 @@ test_mag(uint8_t argc, const Menu::arg *argv)
static int8_t
test_airspeed(uint8_t argc, const Menu::arg *argv)
{
float airspeed_ch = adc.Ch(AIRSPEED_CH);
// Serial.println(adc.Ch(AIRSPEED_CH));
float airspeed_ch = pitot_analog_source.read();
// Serial.println(pitot_analog_source.read());
Serial.printf_P(PSTR("airspeed_ch: %.1f\n"), airspeed_ch);
if (g.airspeed_enabled == false){