APM_Control: reduce the number of parameter saves in autotune
don't save a parameter unless it has changed by 0.1%
This commit is contained in:
parent
ccc7d36493
commit
b4c5f31b17
@ -260,16 +260,29 @@ void AP_AutoTune::check_save(void)
|
|||||||
last_save_ms = hal.scheduler->millis();
|
last_save_ms = hal.scheduler->millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
set a float and save a float if it has changed by more than
|
||||||
|
0.1%. This reduces the number of insignificant EEPROM writes
|
||||||
|
*/
|
||||||
|
void AP_AutoTune::save_float_if_changed(AP_Float &v, float value)
|
||||||
|
{
|
||||||
|
float old_value = v.get();
|
||||||
|
v.set(value);
|
||||||
|
if (value <= 0 || fabsf((value-old_value)/value) > 0.001f) {
|
||||||
|
v.save();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
save a set of gains
|
save a set of gains
|
||||||
*/
|
*/
|
||||||
void AP_AutoTune::save_gains(const ATGains &v)
|
void AP_AutoTune::save_gains(const ATGains &v)
|
||||||
{
|
{
|
||||||
current = last_save;
|
current = last_save;
|
||||||
current.tau.set_and_save_ifchanged(v.tau);
|
save_float_if_changed(current.tau, v.tau);
|
||||||
current.P.set_and_save_ifchanged(v.P);
|
save_float_if_changed(current.P, v.P);
|
||||||
current.I.set_and_save_ifchanged(v.I);
|
save_float_if_changed(current.I, v.I);
|
||||||
current.D.set_and_save_ifchanged(v.D);
|
save_float_if_changed(current.D, v.D);
|
||||||
current.rmax.set_and_save_ifchanged(v.rmax);
|
current.rmax.set_and_save_ifchanged(v.rmax);
|
||||||
current.imax.set_and_save_ifchanged(v.imax);
|
current.imax.set_and_save_ifchanged(v.imax);
|
||||||
last_save = current;
|
last_save = current;
|
||||||
|
@ -85,6 +85,8 @@ private:
|
|||||||
|
|
||||||
void write_log_headers(void);
|
void write_log_headers(void);
|
||||||
void write_log(float servo, float demanded, float achieved);
|
void write_log(float servo, float demanded, float achieved);
|
||||||
|
|
||||||
|
void save_float_if_changed(AP_Float &v, float value);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_AUTOTUNE_H__
|
#endif // __AP_AUTOTUNE_H__
|
||||||
|
Loading…
Reference in New Issue
Block a user