mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Stats: Only reset statistics if the user explicitly sets AP_Stats_RESET parameter to zero.
This allows users to load parameter files (in MP, MAVProxy or any other GCS) without accidentally reseting the statistics, because the AP_STATS_RESET value contained in the parameter file will be ignored (unless it is zero and it is usually not zero). The other statistics parameters are read-only, and the GCS should be clever enough to not set those.
This commit is contained in:
parent
74640c9e65
commit
4996c17a75
@ -33,7 +33,7 @@ const AP_Param::GroupInfo AP_Stats::var_info[] = {
|
|||||||
|
|
||||||
// @Param: _RESET
|
// @Param: _RESET
|
||||||
// @DisplayName: Statistics Reset Time
|
// @DisplayName: Statistics Reset Time
|
||||||
// @Description: Seconds since January 1st 2016 (Unix epoch+1451606400) since statistics reset (set to 0 to reset statistics)
|
// @Description: Seconds since January 1st 2016 (Unix epoch+1451606400) since statistics reset (set to 0 to reset statistics, other set values will be ignored)
|
||||||
// @Units: s
|
// @Units: s
|
||||||
// @ReadOnly: True
|
// @ReadOnly: True
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
@ -104,8 +104,13 @@ void AP_Stats::update()
|
|||||||
last_flush_ms = now_ms;
|
last_flush_ms = now_ms;
|
||||||
}
|
}
|
||||||
const uint32_t params_reset = params.reset;
|
const uint32_t params_reset = params.reset;
|
||||||
if (params_reset != reset || params_reset == 0) {
|
if (params_reset == 0) {
|
||||||
params.bootcount.set_and_save_ifchanged(params_reset == 0 ? 1 : 0);
|
// Only reset statistics if the user explicitly sets AP_STATS_RESET parameter to zero.
|
||||||
|
// This allows users to load parameter files (in MP, MAVProxy or any other GCS) without
|
||||||
|
// accidentally reseting the statistics, because the AP_STATS_RESET value contained in
|
||||||
|
// the parameter file will be ignored (unless it is zero and it is usually not zero).
|
||||||
|
// The other statistics parameters are read-only, and the GCS should be clever enough to not set those.
|
||||||
|
params.bootcount.set_and_save_ifchanged(0);
|
||||||
params.flttime.set_and_save_ifchanged(0);
|
params.flttime.set_and_save_ifchanged(0);
|
||||||
params.runtime.set_and_save_ifchanged(0);
|
params.runtime.set_and_save_ifchanged(0);
|
||||||
uint32_t system_clock = 0; // in seconds
|
uint32_t system_clock = 0; // in seconds
|
||||||
|
Loading…
Reference in New Issue
Block a user