2016-10-13 03:30:04 -03:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
// AP_Stats is used to collect and put to permanent storage data about
|
|
|
|
// the vehicle's autopilot
|
|
|
|
|
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
|
|
|
|
|
|
|
class AP_Stats
|
|
|
|
{
|
|
|
|
public:
|
2018-07-20 17:24:52 -03:00
|
|
|
// constructor
|
|
|
|
AP_Stats();
|
|
|
|
|
2016-10-13 07:44:30 -03:00
|
|
|
// 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)
|
2016-10-13 21:08:17 -03:00
|
|
|
uint32_t runtime; // total wallclock time spent running ArduPilot (seconds)
|
2017-06-08 05:26:19 -03:00
|
|
|
uint32_t reset; // last time AP_Stats parameters were reset (in seconds since AP_Stats Jan 1st 2016)
|
2018-07-20 17:24:52 -03:00
|
|
|
uint32_t flttime_boot; // seconds in flight (or driving), at boot
|
|
|
|
|
2016-10-13 03:30:04 -03:00
|
|
|
void init();
|
|
|
|
|
2016-10-13 06:39:06 -03:00
|
|
|
// copy state into underlying parameters:
|
|
|
|
void flush();
|
|
|
|
|
|
|
|
// periodic update function (e.g. put our values to permanent storage):
|
|
|
|
// call at least 1Hz
|
|
|
|
void update();
|
|
|
|
|
2016-10-13 07:44:30 -03:00
|
|
|
void set_flying(bool b);
|
|
|
|
|
2018-07-20 17:24:52 -03:00
|
|
|
// 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;
|
|
|
|
}
|
|
|
|
|
2016-10-13 03:30:04 -03:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
|
|
|
private:
|
2018-07-20 17:24:52 -03:00
|
|
|
static AP_Stats *_singleton;
|
|
|
|
|
2016-10-13 03:30:04 -03:00
|
|
|
struct {
|
|
|
|
AP_Int16 bootcount;
|
2016-10-13 07:44:30 -03:00
|
|
|
AP_Int32 flttime;
|
2016-10-13 21:08:17 -03:00
|
|
|
AP_Int32 runtime;
|
2016-10-13 21:59:06 -03:00
|
|
|
AP_Int32 reset;
|
2016-10-13 03:30:04 -03:00
|
|
|
} params;
|
|
|
|
|
2016-10-13 21:59:06 -03:00
|
|
|
void copy_variables_from_parameters();
|
|
|
|
|
2016-10-13 06:39:06 -03:00
|
|
|
uint64_t last_flush_ms; // in terms of system uptime
|
|
|
|
const uint16_t flush_interval_ms = 30000;
|
2016-10-13 07:44:30 -03:00
|
|
|
|
|
|
|
uint64_t _flying_ms;
|
2016-10-13 21:08:17 -03:00
|
|
|
uint64_t _last_runtime_ms;
|
2016-10-13 07:44:30 -03:00
|
|
|
|
|
|
|
void update_flighttime();
|
2016-10-13 21:08:17 -03:00
|
|
|
void update_runtime();
|
2020-01-18 17:57:28 -04:00
|
|
|
HAL_Semaphore sem;
|
2016-10-13 03:30:04 -03:00
|
|
|
};
|
2018-07-20 17:24:52 -03:00
|
|
|
|
|
|
|
namespace AP {
|
|
|
|
AP_Stats *stats();
|
|
|
|
};
|