Browse Source

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

this fixes a bug where motors can start on soft reboot
mission-4.1.18
Andrew Tridgell 8 years ago
parent
commit
36a633bc7a
  1. 3
      ArduSub/system.cpp

3
ArduSub/system.cpp

@ -185,6 +185,9 @@ void Sub::init_ardupilot() @@ -185,6 +185,9 @@ void Sub::init_ardupilot()
start_logging(); // create a new log if necessary
}
// disable safety if requested
BoardConfig.init_safety();
hal.console->print("\nInit complete");
// flag that initialisation has completed

Loading…
Cancel
Save