From e3930b45dfdef7bb4001a565a5c9bdc9045ca553 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Thu, 26 May 2016 23:41:29 -0700 Subject: [PATCH] Plane: force the safety_state immediately because we want it to be in effect while we make mixer changes --- ArduPlane/px4_mixer.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduPlane/px4_mixer.cpp b/ArduPlane/px4_mixer.cpp index ecd57be30b..37264aaab8 100644 --- a/ArduPlane/px4_mixer.cpp +++ b/ArduPlane/px4_mixer.cpp @@ -276,6 +276,7 @@ bool Plane::setup_failsafe_mixing(void) // it twice as there have been reports that this call can fail // with a small probability hal.rcout->force_safety_on(); + hal.rcout->force_safety_no_wait(); /* reset any existing mixer in px4io. This shouldn't be needed, * but is good practice */