From c0798730a8314364b9e622e290cf68bd26299c98 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 16 Sep 2012 15:51:01 +1000 Subject: [PATCH] APM: only copy manual channels in failsafe this prevents non-manual channels changing value away from the trim value on startup --- ArduPlane/failsafe.pde | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduPlane/failsafe.pde b/ArduPlane/failsafe.pde index 95e875f8c5..50c267f92e 100644 --- a/ArduPlane/failsafe.pde +++ b/ArduPlane/failsafe.pde @@ -39,8 +39,9 @@ void failsafe_check(uint32_t tnow) // pass RC inputs to outputs every 20ms last_timestamp = tnow; APM_RC.clearOverride(); - for (uint8_t ch=0; ch<8; ch++) { + for (uint8_t ch=0; ch<4; ch++) { APM_RC.OutputCh(ch, APM_RC.InputCh(ch)); } + RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_manual); } }