Plane: only revert a tuning parameter if it has been set

fixes a 2nd transmitter tuning bug found by expntly
This commit is contained in:
Andrew Tridgell 2016-10-14 08:34:54 +11:00
parent f0f4322500
commit b5a2bf2c6f
1 changed files with 5 additions and 1 deletions

View File

@ -275,8 +275,12 @@ void AP_Tuning_Plane::reload_value(uint8_t parm)
default: default:
AP_Float *f = get_param_pointer(parm); AP_Float *f = get_param_pointer(parm);
if (f != nullptr) { if (f != nullptr) {
uint64_t param_bit = (1ULL << parm);
// only reload if we have set this parameter at some point
if (param_bit & have_set) {
f->load(); f->load();
} }
}
break; break;
} }
} }