Copter: call BoardConfig.init_safety() at end of startup

this fixes a bug where motors can start on soft reboot
This commit is contained in:
Andrew Tridgell 2017-04-30 10:48:01 +10:00
parent c5d17a9d92
commit 10b89db498
1 changed files with 3 additions and 0 deletions

View File

@ -316,6 +316,9 @@ void Copter::init_ardupilot()
enable_motor_output();
}
// disable safety if requested
BoardConfig.init_safety();
cliSerial->printf("\nReady to FLY ");
// flag that initialisation has completed