From b5a2bf2c6fe091fc1a8ba26bc85a13fe2b2631a8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 14 Oct 2016 08:34:54 +1100 Subject: [PATCH] Plane: only revert a tuning parameter if it has been set fixes a 2nd transmitter tuning bug found by expntly --- ArduPlane/tuning.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/ArduPlane/tuning.cpp b/ArduPlane/tuning.cpp index 33c409634e..b6947d8bf1 100644 --- a/ArduPlane/tuning.cpp +++ b/ArduPlane/tuning.cpp @@ -275,7 +275,11 @@ void AP_Tuning_Plane::reload_value(uint8_t parm) default: AP_Float *f = get_param_pointer(parm); if (f != nullptr) { - f->load(); + uint64_t param_bit = (1ULL << parm); + // only reload if we have set this parameter at some point + if (param_bit & have_set) { + f->load(); + } } break; }