From a5ed0de2cf50e72b534712a7de098add8abf2e92 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 20 Nov 2012 19:27:52 +1100 Subject: [PATCH] APM: set MANUAL_LEVEL to 1 on successful accel calibration --- ArduPlane/setup.pde | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/ArduPlane/setup.pde b/ArduPlane/setup.pde index e5c69636e1..63cec6147d 100644 --- a/ArduPlane/setup.pde +++ b/ArduPlane/setup.pde @@ -306,7 +306,12 @@ static int8_t setup_accel_scale(uint8_t argc, const Menu::arg *argv) { ins.init(AP_InertialSensor::COLD_START, delay, flash_leds, &timer_scheduler); - ins.calibrate_accel(delay, flash_leds, NULL); + if (ins.calibrate_accel(delay, flash_leds, NULL)) { + if (g.manual_level == 0) { + Serial.println_P(PSTR("Setting MANUAL_LEVEL to 1")); + g.manual_level.set_and_save(1); + } + } report_ins(); return(0); }