From 8df04103b6387a6f539e3364c0a100b511d263d7 Mon Sep 17 00:00:00 2001 From: murata Date: Wed, 29 Sep 2021 00:14:30 +0900 Subject: [PATCH] AP_Stats: Ignore fraudulent posts --- libraries/AP_Stats/AP_Stats.cpp | 2 ++ libraries/AP_Stats/AP_Stats.h | 1 + 2 files changed, 3 insertions(+) diff --git a/libraries/AP_Stats/AP_Stats.cpp b/libraries/AP_Stats/AP_Stats.cpp index 9c82a0e32e84e..be3fda7308848 100644 --- a/libraries/AP_Stats/AP_Stats.cpp +++ b/libraries/AP_Stats/AP_Stats.cpp @@ -52,6 +52,7 @@ AP_Stats::AP_Stats(void) void AP_Stats::copy_variables_from_parameters() { + bootcount = params.bootcount; flttime = params.flttime; runtime = params.runtime; reset = params.reset; @@ -69,6 +70,7 @@ void AP_Stats::init() void AP_Stats::flush() { + params.bootcount.set_and_save_ifchanged(bootcount); params.flttime.set_and_save_ifchanged(flttime); params.runtime.set_and_save_ifchanged(runtime); } diff --git a/libraries/AP_Stats/AP_Stats.h b/libraries/AP_Stats/AP_Stats.h index 411fa6060d08f..5afdea654366d 100644 --- a/libraries/AP_Stats/AP_Stats.h +++ b/libraries/AP_Stats/AP_Stats.h @@ -15,6 +15,7 @@ class AP_Stats // these variables are periodically written into the actual // parameters. If you add a variable here, make sure to update // init() to set initial values from the parameters! + uint32_t bootcount; // total boot count uint32_t flttime; // seconds in flight (or driving) uint32_t runtime; // total wallclock time spent running ArduPilot (seconds) uint32_t reset; // last time AP_Stats parameters were reset (in seconds since AP_Stats Jan 1st 2016)