Browse Source

SRV_Channel: use rc() method to get rc singleton

mission-4.1.18
Peter Barker 7 years ago committed by Randy Mackay
parent
commit
c1a1f4f970
  1. 26
      libraries/SRV_Channel/SRV_Channel_aux.cpp

26
libraries/SRV_Channel/SRV_Channel_aux.cpp

@ -41,12 +41,12 @@ void SRV_Channel::output_ch(void)
} }
if (passthrough_from != -1) { if (passthrough_from != -1) {
// we are doing passthrough from input to output for this channel // we are doing passthrough from input to output for this channel
RC_Channel *rc = RC_Channels::rc_channel(passthrough_from); RC_Channel *c = rc().channel(passthrough_from);
if (rc) { if (c) {
if (SRV_Channels::passthrough_disabled()) { if (SRV_Channels::passthrough_disabled()) {
output_pwm = rc->get_radio_trim(); output_pwm = c->get_radio_trim();
} else { } else {
output_pwm = rc->get_radio_in(); output_pwm = c->get_radio_in();
} }
} }
} }
@ -251,11 +251,11 @@ SRV_Channels::copy_radio_in_out(SRV_Channel::Aux_servo_function_t function, bool
} }
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) { for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
if (channels[i].function.get() == function) { if (channels[i].function.get() == function) {
RC_Channel *rc = RC_Channels::rc_channel(channels[i].ch_num); RC_Channel *c = rc().channel(channels[i].ch_num);
if (rc == nullptr) { if (c == nullptr) {
continue; continue;
} }
channels[i].set_output_pwm(rc->get_radio_in()); channels[i].set_output_pwm(c->get_radio_in());
if (do_input_output) { if (do_input_output) {
channels[i].output_ch(); channels[i].output_ch();
} }
@ -271,11 +271,11 @@ SRV_Channels::copy_radio_in_out_mask(uint16_t mask)
{ {
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) { for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
if ((1U<<i) & mask) { if ((1U<<i) & mask) {
RC_Channel *rc = RC_Channels::rc_channel(channels[i].ch_num); RC_Channel *c = rc().channel(channels[i].ch_num);
if (rc == nullptr) { if (c == nullptr) {
continue; continue;
} }
channels[i].set_output_pwm(rc->get_radio_in()); channels[i].set_output_pwm(c->get_radio_in());
} }
} }
@ -349,11 +349,11 @@ SRV_Channels::set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_C
uint16_t pwm = ch.get_limit_pwm(limit); uint16_t pwm = ch.get_limit_pwm(limit);
ch.set_output_pwm(pwm); ch.set_output_pwm(pwm);
if (ch.function.get() == SRV_Channel::k_manual) { if (ch.function.get() == SRV_Channel::k_manual) {
RC_Channel *rc = RC_Channels::rc_channel(ch.ch_num); RC_Channel *c = rc().channel(ch.ch_num);
if (rc != nullptr) { if (c != nullptr) {
// in order for output_ch() to work for k_manual we // in order for output_ch() to work for k_manual we
// also have to override radio_in // also have to override radio_in
rc->set_radio_in(pwm); c->set_radio_in(pwm);
} }
} }
} }

Loading…
Cancel
Save