AP_Stats: runtime
This commit is contained in:
parent
d2b7749af3
commit
e6adbceb3e
@ -15,6 +15,12 @@ const AP_Param::GroupInfo AP_Stats::var_info[] = {
|
|||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_FLTTIME", 1, AP_Stats, params.flttime, 0),
|
AP_GROUPINFO("_FLTTIME", 1, AP_Stats, params.flttime, 0),
|
||||||
|
|
||||||
|
// @Param: _RUNTIME
|
||||||
|
// @DisplayName: Total RunTime
|
||||||
|
// @Description: Total time autopilot has run
|
||||||
|
// @User: Standard
|
||||||
|
AP_GROUPINFO("_RUNTIME", 2, AP_Stats, params.runtime, 0),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -24,11 +30,14 @@ void AP_Stats::init()
|
|||||||
|
|
||||||
// initialise our variables from parameters:
|
// initialise our variables from parameters:
|
||||||
flttime = params.flttime;
|
flttime = params.flttime;
|
||||||
|
runtime = params.runtime;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void AP_Stats::flush()
|
void AP_Stats::flush()
|
||||||
{
|
{
|
||||||
params.flttime.set_and_save(flttime);
|
params.flttime.set_and_save(flttime);
|
||||||
|
params.runtime.set_and_save(runtime);
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_Stats::update_flighttime()
|
void AP_Stats::update_flighttime()
|
||||||
@ -41,11 +50,20 @@ void AP_Stats::update_flighttime()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void AP_Stats::update_runtime()
|
||||||
|
{
|
||||||
|
const uint32_t now = AP_HAL::millis();
|
||||||
|
const uint32_t delta = (now - _last_runtime_ms)/1000;
|
||||||
|
runtime += delta;
|
||||||
|
_last_runtime_ms += delta*1000;
|
||||||
|
}
|
||||||
|
|
||||||
void AP_Stats::update()
|
void AP_Stats::update()
|
||||||
{
|
{
|
||||||
const uint32_t now_ms = AP_HAL::millis();
|
const uint32_t now_ms = AP_HAL::millis();
|
||||||
if (now_ms - last_flush_ms > flush_interval_ms) {
|
if (now_ms - last_flush_ms > flush_interval_ms) {
|
||||||
update_flighttime();
|
update_flighttime();
|
||||||
|
update_runtime();
|
||||||
flush();
|
flush();
|
||||||
last_flush_ms = now_ms;
|
last_flush_ms = now_ms;
|
||||||
}
|
}
|
||||||
|
@ -14,6 +14,7 @@ public:
|
|||||||
// parameters. If you add a variable here, make sure to update
|
// parameters. If you add a variable here, make sure to update
|
||||||
// init() to set initial values from the parameters!
|
// init() to set initial values from the parameters!
|
||||||
uint32_t flttime; // seconds in flight (or driving)
|
uint32_t flttime; // seconds in flight (or driving)
|
||||||
|
uint32_t runtime; // total wallclock time spent running ArduPilot (seconds)
|
||||||
|
|
||||||
void init();
|
void init();
|
||||||
|
|
||||||
@ -33,13 +34,16 @@ private:
|
|||||||
struct {
|
struct {
|
||||||
AP_Int16 bootcount;
|
AP_Int16 bootcount;
|
||||||
AP_Int32 flttime;
|
AP_Int32 flttime;
|
||||||
|
AP_Int32 runtime;
|
||||||
} params;
|
} params;
|
||||||
|
|
||||||
uint64_t last_flush_ms; // in terms of system uptime
|
uint64_t last_flush_ms; // in terms of system uptime
|
||||||
const uint16_t flush_interval_ms = 30000;
|
const uint16_t flush_interval_ms = 30000;
|
||||||
|
|
||||||
uint64_t _flying_ms;
|
uint64_t _flying_ms;
|
||||||
|
uint64_t _last_runtime_ms;
|
||||||
|
|
||||||
void update_flighttime();
|
void update_flighttime();
|
||||||
|
void update_runtime();
|
||||||
|
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user