Commander: Do not save params on already saved param update

This commit is contained in:
Lorenz Meier 2016-01-22 11:33:40 +01:00
parent 19b81b9ab2
commit 85c49ff642
2 changed files with 11 additions and 9 deletions

View File

@ -1 +1,2 @@
uint64 timestamp # time at which the latest parameter was updated
bool saved # wether the change has already been saved to disk

View File

@ -1509,13 +1509,13 @@ int commander_thread_main(int argc, char *argv[])
/* EPH / EPV */
param_get(_param_eph, &eph_threshold);
param_get(_param_epv, &epv_threshold);
}
/* Set flag to autosave parameters if necessary */
if (updated && autosave_params != 0) {
if (updated && autosave_params != 0 && param_changed.saved == false) {
/* trigger an autosave */
need_param_autosave = true;
}
}
orb_check(sp_man_sub, &updated);
@ -1574,7 +1574,8 @@ int commander_thread_main(int argc, char *argv[])
bool hotplug_timeout = hrt_elapsed_time(&commander_boot_timestamp) > HOTPLUG_SENS_TIMEOUT;
/* Perform airspeed check only if circuit breaker is not
* engaged and it's not a rotary wing */
* engaged and it's not a rotary wing
*/
if (!status.circuit_breaker_engaged_airspd_check && !status.is_rotary_wing) {
chAirspeed = true;
}