mirror of https://github.com/ArduPilot/ardupilot
AP_Tuning: detect change to TUNE_PARMSET while tuning
This commit is contained in:
parent
6d1c7c9082
commit
f69806deff
|
@ -146,6 +146,16 @@ void AP_Tuning::check_input(uint8_t flightmode)
|
||||||
range.set(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();
|
check_selector_switch();
|
||||||
|
|
||||||
if (selector_start_ms) {
|
if (selector_start_ms) {
|
||||||
|
@ -153,9 +163,6 @@ void AP_Tuning::check_input(uint8_t flightmode)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (current_parm == 0) {
|
|
||||||
next_parameter();
|
|
||||||
}
|
|
||||||
if (current_parm == 0) {
|
if (current_parm == 0) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
|
@ -44,7 +44,7 @@ private:
|
||||||
AP_Int16 channel_min;
|
AP_Int16 channel_min;
|
||||||
AP_Int16 channel_max;
|
AP_Int16 channel_max;
|
||||||
AP_Int8 selector;
|
AP_Int8 selector;
|
||||||
AP_Int8 parmset;
|
AP_Int16 parmset;
|
||||||
AP_Float range;
|
AP_Float range;
|
||||||
|
|
||||||
// when selector was triggered
|
// when selector was triggered
|
||||||
|
|
Loading…
Reference in New Issue