From 96c7d9dde8f5713ba8e4b135336589a7043e706f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 11 Oct 2016 20:30:08 +1100 Subject: [PATCH] RC_Channel: make output_trim() go via _radio_out this ensures that _radio_out always contains the value that would be output to the channel. This will be used by the SRV_Channels object --- libraries/RC_Channel/RC_Channel.cpp | 5 +++-- libraries/RC_Channel/RC_Channel.h | 2 +- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 76458ba691..9fe2626faa 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -482,9 +482,10 @@ void RC_Channel::output() const hal.rcout->write(_ch_out, _radio_out); } -void RC_Channel::output_trim() const +void RC_Channel::output_trim() { - hal.rcout->write(_ch_out, _radio_trim); + _radio_out = _radio_trim; + output(); } void RC_Channel::output_trim_all() diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 4608a2a7f5..190ac13584 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -106,7 +106,7 @@ public: int16_t pwm_to_range_dz(uint16_t dead_zone); int16_t range_to_pwm(); void output() const; - void output_trim() const; + void output_trim(); static void output_trim_all(); static void setup_failsafe_trim_mask(uint16_t chmask); static void setup_failsafe_trim_all();