From 3e55bf7d1269bc486270de9ba71d5fe083161ec5 Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar Do Carmo Lucas" Date: Thu, 8 Jun 2017 10:26:19 +0200 Subject: [PATCH] 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. --- libraries/AP_Stats/AP_Stats.cpp | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Stats/AP_Stats.cpp b/libraries/AP_Stats/AP_Stats.cpp index 2b5343a0876cb..76c66b4edb16e 100644 --- a/libraries/AP_Stats/AP_Stats.cpp +++ b/libraries/AP_Stats/AP_Stats.cpp @@ -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 @@ -104,8 +104,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