From f1d37fc0517584e4628bc21e25f15d4e4db8d880 Mon Sep 17 00:00:00 2001 From: Tatsuya Yamaguchi Date: Mon, 18 Dec 2023 10:42:05 +0900 Subject: [PATCH] AP_Stats: update flight time on disarm --- libraries/AP_Stats/AP_Stats.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Stats/AP_Stats.cpp b/libraries/AP_Stats/AP_Stats.cpp index 76c66b4edb..5a50534219 100644 --- a/libraries/AP_Stats/AP_Stats.cpp +++ b/libraries/AP_Stats/AP_Stats.cpp @@ -72,6 +72,7 @@ void AP_Stats::flush() { params.flttime.set_and_save_ifchanged(flttime); params.runtime.set_and_save_ifchanged(runtime); + last_flush_ms = AP_HAL::millis(); } void AP_Stats::update_flighttime() @@ -101,7 +102,6 @@ void AP_Stats::update() update_flighttime(); update_runtime(); flush(); - last_flush_ms = now_ms; } const uint32_t params_reset = params.reset; if (params_reset == 0) { @@ -136,7 +136,11 @@ void AP_Stats::set_flying(const bool is_flying) _flying_ms = AP_HAL::millis(); } } else { - update_flighttime(); + if (_flying_ms) { + update_flighttime(); + update_runtime(); + flush(); + } _flying_ms = 0; } }