mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed bug in transmitter tuning
This bug affects transmitter tuning of parameters that have never been saved to eeprom and don't have a default value in the AP_Param tables. When reverting these parameters became zero which could lead to a crash many thanks to expntly for finding this bug!
This commit is contained in:
parent
412dca1615
commit
70265f9100
|
@ -239,6 +239,18 @@ void AP_Tuning_Plane::set_value(uint8_t parm, float value)
|
|||
default:
|
||||
AP_Float *f = get_param_pointer(parm);
|
||||
if (f != nullptr) {
|
||||
uint64_t param_bit = (1ULL << parm);
|
||||
if (!(param_bit & have_set)) {
|
||||
// first time this param has been set by tuning. We
|
||||
// need to see if a reversion value is available in
|
||||
// FRAM, and if not then save one
|
||||
float current_value = f->get();
|
||||
if (!f->load()) {
|
||||
// there is no value in FRAM, set one
|
||||
f->set_and_save(current_value);
|
||||
}
|
||||
have_set |= param_bit;
|
||||
}
|
||||
f->set_and_notify(value);
|
||||
}
|
||||
break;
|
||||
|
|
|
@ -97,4 +97,7 @@ private:
|
|||
static const uint8_t tuning_set_ang_roll_pitch[];
|
||||
static const uint8_t tuning_set_vxy[];
|
||||
static const uint8_t tuning_set_az[];
|
||||
|
||||
// mask of what params have been set
|
||||
uint64_t have_set;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue