mirror of https://github.com/ArduPilot/ardupilot
AP_Stats: make singleton and add flighttime accessor
This commit is contained in:
parent
ea3e523d28
commit
e26028f572
|
@ -42,11 +42,20 @@ const AP_Param::GroupInfo AP_Stats::var_info[] = {
|
|||
AP_GROUPEND
|
||||
};
|
||||
|
||||
AP_Stats *AP_Stats::_singleton;
|
||||
|
||||
// constructor
|
||||
AP_Stats::AP_Stats(void)
|
||||
{
|
||||
_singleton = this;
|
||||
}
|
||||
|
||||
void AP_Stats::copy_variables_from_parameters()
|
||||
{
|
||||
flttime = params.flttime;
|
||||
runtime = params.runtime;
|
||||
reset = params.reset;
|
||||
flttime_boot = flttime;
|
||||
}
|
||||
|
||||
void AP_Stats::init()
|
||||
|
@ -121,3 +130,17 @@ void AP_Stats::set_flying(const bool is_flying)
|
|||
_flying_ms = 0;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
get time in flight since boot
|
||||
*/
|
||||
uint32_t AP_Stats::get_flight_time_s(void)
|
||||
{
|
||||
update_flighttime();
|
||||
return flttime - flttime_boot;
|
||||
}
|
||||
|
||||
AP_Stats *AP::stats(void)
|
||||
{
|
||||
return AP_Stats::get_singleton();
|
||||
}
|
||||
|
|
|
@ -9,6 +9,8 @@
|
|||
class AP_Stats
|
||||
{
|
||||
public:
|
||||
// constructor
|
||||
AP_Stats();
|
||||
|
||||
// these variables are periodically written into the actual
|
||||
// parameters. If you add a variable here, make sure to update
|
||||
|
@ -16,6 +18,7 @@ public:
|
|||
uint32_t flttime; // seconds in flight (or driving)
|
||||
uint32_t runtime; // total wallclock time spent running ArduPilot (seconds)
|
||||
uint32_t reset; // last time parameters were reset
|
||||
uint32_t flttime_boot; // seconds in flight (or driving), at boot
|
||||
|
||||
void init();
|
||||
|
||||
|
@ -28,9 +31,24 @@ public:
|
|||
|
||||
void set_flying(bool b);
|
||||
|
||||
// accessor for is_flying
|
||||
bool get_is_flying(void) {
|
||||
return _flying_ms != 0;
|
||||
}
|
||||
|
||||
// accessor for flighttime. Returns 0 if not flying, otherwise
|
||||
// total time flying since boot in seconds
|
||||
uint32_t get_flight_time_s(void);
|
||||
|
||||
// get singleton
|
||||
static AP_Stats *get_singleton(void) {
|
||||
return _singleton;
|
||||
}
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
static AP_Stats *_singleton;
|
||||
|
||||
struct {
|
||||
AP_Int16 bootcount;
|
||||
|
@ -51,3 +69,7 @@ private:
|
|||
void update_runtime();
|
||||
|
||||
};
|
||||
|
||||
namespace AP {
|
||||
AP_Stats *stats();
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue