From b357a254f63bfee8b82c01318d8b8ddc8226671e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 11 Aug 2016 14:11:03 +1000 Subject: [PATCH] Plane: use force_safety_no_wait() when re-enabling safety off in mixer --- ArduPlane/px4_mixer.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduPlane/px4_mixer.cpp b/ArduPlane/px4_mixer.cpp index ce8309db77..333bb60f63 100644 --- a/ArduPlane/px4_mixer.cpp +++ b/ArduPlane/px4_mixer.cpp @@ -402,6 +402,7 @@ failed: // restore safety state if it was previously armed if (old_state == AP_HAL::Util::SAFETY_ARMED) { hal.rcout->force_safety_off(); + hal.rcout->force_safety_no_wait(); } if (!ret) { // clear out the mixer CRC so that we will attempt to send it again