From d1791bab76525414717051a26d0ed764846797d3 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 25 May 2013 12:21:29 +0900 Subject: [PATCH] Copter: fix barometer cli test --- ArduCopter/sensors.pde | 1 + ArduCopter/system.pde | 11 ++++++----- ArduCopter/test.pde | 21 +++++++++++---------- 3 files changed, 18 insertions(+), 15 deletions(-) diff --git a/ArduCopter/sensors.pde b/ArduCopter/sensors.pde index 7662d5d4b0..46eb89022c 100644 --- a/ArduCopter/sensors.pde +++ b/ArduCopter/sensors.pde @@ -16,6 +16,7 @@ static void init_sonar(void) static void init_barometer(void) { + gcs_send_text_P(SEVERITY_LOW, PSTR("Calibrating barometer")); barometer.calibrate(); gcs_send_text_P(SEVERITY_LOW, PSTR("barometer calibration complete")); } diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 8b03fb2173..a3ffef4e23 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -142,6 +142,10 @@ static void init_ardupilot() // load parameters from EEPROM load_parameters(); +#if HIL_MODE != HIL_MODE_ATTITUDE + barometer.init(); +#endif + // init the GCS gcs0.init(hal.uartA); @@ -197,9 +201,6 @@ static void init_ardupilot() // begin filtering the ADC Gyros adc.Init(); // APM ADC library initialization #endif // CONFIG_ADC - - barometer.init(); - #endif // HIL_MODE // Do GPS init @@ -251,8 +252,8 @@ static void init_ardupilot() #endif #if FRAME_CONFIG == HELI_FRAME -// initialise controller filters -init_rate_controllers(); + // initialise controller filters + init_rate_controllers(); #endif // HELI_FRAME // initialize commands diff --git a/ArduCopter/test.pde b/ArduCopter/test.pde index 60f47ce70c..29011438e4 100644 --- a/ArduCopter/test.pde +++ b/ArduCopter/test.pde @@ -67,9 +67,9 @@ const struct Menu::command test_menu_commands[] PROGMEM = { {"tune", test_tuning}, {"relay", test_relay}, {"wp", test_wp}, -// {"toy", test_toy}, +// {"toy", test_toy}, #if HIL_MODE != HIL_MODE_ATTITUDE && HIL_MODE != HIL_MODE_SENSORS - {"altitude", test_baro}, + {"baro", test_baro}, {"sonar", test_sonar}, #endif {"compass", test_mag}, @@ -413,20 +413,21 @@ test_wp(uint8_t argc, const Menu::arg *argv) static int8_t test_baro(uint8_t argc, const Menu::arg *argv) { + int32_t alt; print_hit_enter(); init_barometer(); while(1) { delay(100); - int32_t alt = read_barometer(); // calls barometer.read() + alt = read_barometer(); - float pres = barometer.get_pressure(); - int16_t temp = barometer.get_temperature(); - int32_t raw_pres = barometer.get_raw_pressure(); - int32_t raw_temp = barometer.get_raw_temp(); - cliSerial->printf_P(PSTR("alt: %ldcm, pres: %fmbar, temp: %d/100degC," - " raw pres: %ld, raw temp: %ld\n"), - (long)alt, pres, (int)temp, (long)raw_pres, (long)raw_temp); + if (!barometer.healthy) { + cliSerial->println_P(PSTR("not healthy")); + } else { + cliSerial->printf_P(PSTR("Alt: %0.2fm, Raw: %f Temperature: %.1f\n"), + alt / 100.0, + barometer.get_pressure(), 0.1*barometer.get_temperature()); + } if(cliSerial->available() > 0) { return (0); }