Skip to content

Commit

Permalink
AP_Stats: update flight time on disarm
Browse files Browse the repository at this point in the history
  • Loading branch information
tatsuy authored and peterbarker committed Apr 5, 2024
1 parent 9dbc61f commit f1d37fc
Showing 1 changed file with 6 additions and 2 deletions.
8 changes: 6 additions & 2 deletions libraries/AP_Stats/AP_Stats.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down Expand Up @@ -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) {
Expand Down Expand Up @@ -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;
}
}
Expand Down

0 comments on commit f1d37fc

Please sign in to comment.