From b8c1367aac6065212058b20a14250d4b85b0acb8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 10 Aug 2023 09:00:41 +1000 Subject: [PATCH] SRV_Channel: avoid using bad RC data in passthrough code we may not have valid input but not be at the stage of declaring an RC failsafe. --- libraries/SRV_Channel/SRV_Channel_aux.cpp | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/libraries/SRV_Channel/SRV_Channel_aux.cpp b/libraries/SRV_Channel/SRV_Channel_aux.cpp index 5b5fc63ef8..50557eed1b 100644 --- a/libraries/SRV_Channel/SRV_Channel_aux.cpp +++ b/libraries/SRV_Channel/SRV_Channel_aux.cpp @@ -59,10 +59,18 @@ void SRV_Channel::output_ch(void) // non-mapped rc passthrough int16_t radio_in = c->get_radio_in(); if (passthrough_mapped) { - if ( ((1U<norm_input_dz() * 4500); + } else { + // no valid input. If we are in radio + // failsafe then go to trim values (if + // configured for this channel). Otherwise + // use the last-good value + if ( ((1U<