Browse Source

AP_Tuning: ignore tuning selector switch unless valid RC input

master
Peter Barker 6 years ago committed by Tom Pittenger
parent
commit
afd63c05ec
  1. 4
      libraries/AP_Tuning/AP_Tuning.cpp

4
libraries/AP_Tuning/AP_Tuning.cpp

@ -65,6 +65,10 @@ void AP_Tuning::check_selector_switch(void) @@ -65,6 +65,10 @@ void AP_Tuning::check_selector_switch(void)
// no selector switch enabled
return;
}
if (!rc().has_valid_input()) {
selector_start_ms = 0;
return;
}
RC_Channel *selchan = rc().channel(selector-1);
if (selchan == nullptr) {
return;

Loading…
Cancel
Save