mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
APM: set MANUAL_LEVEL to 1 on successful accel calibration
This commit is contained in:
parent
85e050f16c
commit
a5ed0de2cf
@ -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);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user