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
This commit is contained in:
parent
c7f738c284
commit
96c7d9dde8
@ -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()
|
||||
|
@ -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();
|
||||
|
Loading…
Reference in New Issue
Block a user