Browse Source

RC_Channel: prevent a warning message for assigned RC channels

master
Andrew Tridgell 9 years ago
parent
commit
9941c91d36
  1. 3
      libraries/RC_Channel/RC_Channel_aux.cpp

3
libraries/RC_Channel/RC_Channel_aux.cpp

@ -391,6 +391,9 @@ bool RC_Channel_aux::set_aux_channel_default(RC_Channel_aux::Aux_servo_function_ @@ -391,6 +391,9 @@ bool RC_Channel_aux::set_aux_channel_default(RC_Channel_aux::Aux_servo_function_
for (uint8_t i=0; i<RC_AUX_MAX_CHANNELS; i++) {
if (_aux_channels[i] && _aux_channels[i]->_ch_out == channel) {
if (_aux_channels[i]->function != k_none) {
if (_aux_channels[i]->function == function) {
return true;
}
hal.console->printf("Channel %u already assigned %u\n",
(unsigned)channel,
(unsigned)_aux_channels[i]->function);

Loading…
Cancel
Save