mirror of https://github.com/ArduPilot/ardupilot
AP_BoardConfig: Remove the usage of force_safety_no_wait
This commit is contained in:
parent
b40c20aea2
commit
53860b53ac
|
@ -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…
Reference in New Issue