Browse Source

AP_BoardConfig: Remove the usage of force_safety_no_wait

master
Michael du Breuil 6 years ago committed by Andrew Tridgell
parent
commit
53860b53ac
  1. 1
      libraries/AP_BoardConfig/board_drivers.cpp

1
libraries/AP_BoardConfig/board_drivers.cpp

@ -37,7 +37,6 @@ void AP_BoardConfig::board_init_safety() @@ -37,7 +37,6 @@ void AP_BoardConfig::board_init_safety()
}
if (force_safety_off) {
hal.rcout->force_safety_off();
hal.rcout->force_safety_no_wait();
// wait until safety has been turned off
uint8_t count = 20;
while (hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_ARMED && count--) {

Loading…
Cancel
Save