mirror of https://github.com/ArduPilot/ardupilot
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:
parent
f0f4322500
commit
b5a2bf2c6f
|
@ -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;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue