diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 9164f4a60b..bba5500a35 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -410,6 +410,18 @@ void RC_Channel::output_trim_all() } } +/* + setup the failsafe value to the trim value for all channels + */ +void RC_Channel::setup_failsafe_trim_all() +{ + for (uint8_t i=0; iset_failsafe_pwm(1U<radio_trim); + } + } +} + void RC_Channel::input() { diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 8f619fdb69..8c473cef4e 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -100,6 +100,7 @@ public: void output() const; void output_trim() const; static void output_trim_all(); + static void setup_failsafe_trim_all(); uint16_t read() const; void input(); void enable_out();