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<