mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-29 12:08:32 -04:00
AP_Stats: a periodic update function, flttime and runtime
This commit is contained in:
parent
df07cb525a
commit
be13de79a4
@ -16,3 +16,16 @@ void AP_Stats::init()
|
||||
{
|
||||
params.bootcount.set_and_save(params.bootcount+1);
|
||||
}
|
||||
|
||||
void AP_Stats::flush()
|
||||
{
|
||||
}
|
||||
|
||||
void AP_Stats::update()
|
||||
{
|
||||
const uint32_t now_ms = AP_HAL::millis();
|
||||
if (now_ms - last_flush_ms > flush_interval_ms) {
|
||||
flush();
|
||||
last_flush_ms = now_ms;
|
||||
}
|
||||
}
|
||||
|
@ -12,6 +12,13 @@ public:
|
||||
|
||||
void init();
|
||||
|
||||
// copy state into underlying parameters:
|
||||
void flush();
|
||||
|
||||
// periodic update function (e.g. put our values to permanent storage):
|
||||
// call at least 1Hz
|
||||
void update();
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
@ -20,4 +27,6 @@ private:
|
||||
AP_Int16 bootcount;
|
||||
} params;
|
||||
|
||||
uint64_t last_flush_ms; // in terms of system uptime
|
||||
const uint16_t flush_interval_ms = 30000;
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user