AP_Stats: AP_Stats flighttime

This commit is contained in:
Peter Barker 2016-10-13 21:44:30 +11:00 committed by Randy Mackay
parent 1bb6350a67
commit 77064852c4
2 changed files with 46 additions and 0 deletions

View File

@ -9,23 +9,56 @@ const AP_Param::GroupInfo AP_Stats::var_info[] = {
// @User: Standard
AP_GROUPINFO("_BOOTCNT", 0, AP_Stats, params.bootcount, 0),
// @Param: _FLTTIME
// @DisplayName: Total FlightTime
// @Description: Total FlightTime (seconds)
// @User: Standard
AP_GROUPINFO("_FLTTIME", 1, AP_Stats, params.flttime, 0),
AP_GROUPEND
};
void AP_Stats::init()
{
params.bootcount.set_and_save(params.bootcount+1);
// initialise our variables from parameters:
flttime = params.flttime;
}
void AP_Stats::flush()
{
params.flttime.set_and_save(flttime);
}
void AP_Stats::update_flighttime()
{
if (_flying_ms) {
const uint32_t now = AP_HAL::millis();
const uint32_t delta = (now - _flying_ms)/1000;
flttime += delta;
_flying_ms += delta*1000;
}
}
void AP_Stats::update()
{
const uint32_t now_ms = AP_HAL::millis();
if (now_ms - last_flush_ms > flush_interval_ms) {
update_flighttime();
flush();
last_flush_ms = now_ms;
}
}
void AP_Stats::set_flying(const bool is_flying)
{
if (is_flying) {
if (!_flying_ms) {
_flying_ms = AP_HAL::millis();
}
} else {
update_flighttime();
_flying_ms = 0;
}
}

View File

@ -10,6 +10,11 @@ class AP_Stats
{
public:
// 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 flttime; // seconds in flight (or driving)
void init();
// copy state into underlying parameters:
@ -19,14 +24,22 @@ public:
// call at least 1Hz
void update();
void set_flying(bool b);
static const struct AP_Param::GroupInfo var_info[];
private:
struct {
AP_Int16 bootcount;
AP_Int32 flttime;
} params;
uint64_t last_flush_ms; // in terms of system uptime
const uint16_t flush_interval_ms = 30000;
uint64_t _flying_ms;
void update_flighttime();
};