Rover: 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:00 +10:00
parent f151fd3691
commit c5d17a9d92
1 changed files with 3 additions and 0 deletions

View File

@ -217,6 +217,9 @@ void Rover::init_ardupilot()
// set the correct flight mode // set the correct flight mode
// --------------------------- // ---------------------------
reset_control_switch(); reset_control_switch();
// disable safety if requested
BoardConfig.init_safety();
} }
//********************************************************************************* //*********************************************************************************