From f69806deffe2d046120628c8c140ad0b20e29667 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 8 May 2016 14:35:40 +1000 Subject: [PATCH] AP_Tuning: detect change to TUNE_PARMSET while tuning --- libraries/AP_Tuning/AP_Tuning.cpp | 13 ++++++++++--- libraries/AP_Tuning/AP_Tuning.h | 2 +- 2 files changed, 11 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Tuning/AP_Tuning.cpp b/libraries/AP_Tuning/AP_Tuning.cpp index 4c7ed88309..10e68cab49 100644 --- a/libraries/AP_Tuning/AP_Tuning.cpp +++ b/libraries/AP_Tuning/AP_Tuning.cpp @@ -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) return; } - if (current_parm == 0) { - next_parameter(); - } if (current_parm == 0) { return; } diff --git a/libraries/AP_Tuning/AP_Tuning.h b/libraries/AP_Tuning/AP_Tuning.h index 792542db7a..1dff563a13 100644 --- a/libraries/AP_Tuning/AP_Tuning.h +++ b/libraries/AP_Tuning/AP_Tuning.h @@ -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