From cf0741f6fd534d539002897abfa8c25a3aac9293 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 25 Aug 2014 19:45:39 +1000 Subject: [PATCH] Plane: don't do failsafe passthru with no RC input thanks to Klrill-ka for the suggestion fixes issue #1302 --- ArduPlane/failsafe.pde | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/ArduPlane/failsafe.pde b/ArduPlane/failsafe.pde index beb7acd7a0..3d96102707 100644 --- a/ArduPlane/failsafe.pde +++ b/ArduPlane/failsafe.pde @@ -37,8 +37,14 @@ void failsafe_check(void) } if (in_failsafe && tnow - last_timestamp > 20000) { - // pass RC inputs to outputs every 20ms last_timestamp = tnow; + + if (hal.rcin->num_channels() == 0) { + // we don't have any RC input to pass through + return; + } + + // pass RC inputs to outputs every 20ms hal.rcin->clear_overrides(); channel_roll->radio_out = channel_roll->read(); channel_pitch->radio_out = channel_pitch->read();