diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 48b09632cf..76458ba691 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -496,16 +496,24 @@ void RC_Channel::output_trim_all() } } +/* + setup the failsafe value to the trim value for all channels in chmask + */ +void RC_Channel::setup_failsafe_trim_mask(uint16_t chmask) +{ + for (uint8_t i=0; iset_failsafe_pwm(1U<_radio_trim); + } + } +} + /* 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); - } - } + setup_failsafe_trim_mask(0xFFFF); } void diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 75f59761bd..3da2fe5929 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -108,6 +108,7 @@ public: void output() const; void output_trim() const; static void output_trim_all(); + static void setup_failsafe_trim_mask(uint16_t chmask); static void setup_failsafe_trim_all(); uint16_t read() const; void input();