Skip to content

Commit

Permalink
AP_Stats: Only reset statistics if the user explicitly sets AP_Stats_…
Browse files Browse the repository at this point in the history
…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.
  • Loading branch information
amilcarlucas committed Sep 3, 2020
1 parent bfc35db commit e7927bb
Showing 1 changed file with 8 additions and 3 deletions.
11 changes: 8 additions & 3 deletions libraries/AP_Stats/AP_Stats.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ const AP_Param::GroupInfo AP_Stats::var_info[] = {

// @Param: _RESET
// @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
// @ReadOnly: True
// @User: Standard
Expand Down Expand Up @@ -103,8 +103,13 @@ void AP_Stats::update()
last_flush_ms = now_ms;
}
const uint32_t params_reset = params.reset;
if (params_reset != reset || params_reset == 0) {
params.bootcount.set_and_save_ifchanged(params_reset == 0 ? 1 : 0);
if (params_reset == 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.runtime.set_and_save_ifchanged(0);
uint32_t system_clock = 0; // in seconds
Expand Down

0 comments on commit e7927bb

Please sign in to comment.