mirror of https://github.com/ArduPilot/ardupilot
AP_Stats: update flight time on disarm
This commit is contained in:
parent
9dbc61f85b
commit
f1d37fc051
|
@ -72,6 +72,7 @@ void AP_Stats::flush()
|
||||||
{
|
{
|
||||||
params.flttime.set_and_save_ifchanged(flttime);
|
params.flttime.set_and_save_ifchanged(flttime);
|
||||||
params.runtime.set_and_save_ifchanged(runtime);
|
params.runtime.set_and_save_ifchanged(runtime);
|
||||||
|
last_flush_ms = AP_HAL::millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_Stats::update_flighttime()
|
void AP_Stats::update_flighttime()
|
||||||
|
@ -101,7 +102,6 @@ void AP_Stats::update()
|
||||||
update_flighttime();
|
update_flighttime();
|
||||||
update_runtime();
|
update_runtime();
|
||||||
flush();
|
flush();
|
||||||
last_flush_ms = now_ms;
|
|
||||||
}
|
}
|
||||||
const uint32_t params_reset = params.reset;
|
const uint32_t params_reset = params.reset;
|
||||||
if (params_reset == 0) {
|
if (params_reset == 0) {
|
||||||
|
@ -136,7 +136,11 @@ void AP_Stats::set_flying(const bool is_flying)
|
||||||
_flying_ms = AP_HAL::millis();
|
_flying_ms = AP_HAL::millis();
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
|
if (_flying_ms) {
|
||||||
update_flighttime();
|
update_flighttime();
|
||||||
|
update_runtime();
|
||||||
|
flush();
|
||||||
|
}
|
||||||
_flying_ms = 0;
|
_flying_ms = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue