Browse Source

AP_Tuning: detect change to TUNE_PARMSET while tuning

master
Andrew Tridgell 9 years ago
parent
commit
f69806deff
  1. 13
      libraries/AP_Tuning/AP_Tuning.cpp
  2. 2
      libraries/AP_Tuning/AP_Tuning.h

13
libraries/AP_Tuning/AP_Tuning.cpp

@ -145,6 +145,16 @@ void AP_Tuning::check_input(uint8_t flightmode) @@ -145,6 +145,16 @@ void AP_Tuning::check_input(uint8_t flightmode)
if (range < 1.1f) {
range.set(1.1f);
}
if (current_parm == 0) {
next_parameter();
}
// cope with user changing parmset while tuning
if (current_set != parmset) {
re_center();
}
current_set = parmset;
check_selector_switch();
@ -153,9 +163,6 @@ void AP_Tuning::check_input(uint8_t flightmode) @@ -153,9 +163,6 @@ void AP_Tuning::check_input(uint8_t flightmode)
return;
}
if (current_parm == 0) {
next_parameter();
}
if (current_parm == 0) {
return;
}

2
libraries/AP_Tuning/AP_Tuning.h

@ -44,7 +44,7 @@ private: @@ -44,7 +44,7 @@ private:
AP_Int16 channel_min;
AP_Int16 channel_max;
AP_Int8 selector;
AP_Int8 parmset;
AP_Int16 parmset;
AP_Float range;
// when selector was triggered

Loading…
Cancel
Save