APM:Libraries
AP_Stats.h
Go to the documentation of this file.
1 #pragma once
2 
3 // AP_Stats is used to collect and put to permanent storage data about
4 // the vehicle's autopilot
5 
6 #include <AP_Common/AP_Common.h>
7 #include <AP_Param/AP_Param.h>
8 
9 class AP_Stats
10 {
11 public:
12 
13  // these variables are periodically written into the actual
14  // parameters. If you add a variable here, make sure to update
15  // init() to set initial values from the parameters!
16  uint32_t flttime; // seconds in flight (or driving)
17  uint32_t runtime; // total wallclock time spent running ArduPilot (seconds)
18  uint32_t reset; // last time parameters were reset
19 
20  void init();
21 
22  // copy state into underlying parameters:
23  void flush();
24 
25  // periodic update function (e.g. put our values to permanent storage):
26  // call at least 1Hz
27  void update();
28 
29  void set_flying(bool b);
30 
31  static const struct AP_Param::GroupInfo var_info[];
32 
33 private:
34 
35  struct {
36  AP_Int16 bootcount;
37  AP_Int32 flttime;
38  AP_Int32 runtime;
39  AP_Int32 reset;
40  } params;
41 
43 
44  uint64_t last_flush_ms; // in terms of system uptime
45  const uint16_t flush_interval_ms = 30000;
46 
47  uint64_t _flying_ms;
48  uint64_t _last_runtime_ms;
49 
50  void update_flighttime();
51  void update_runtime();
52 
53 };
AP_Int32 flttime
Definition: AP_Stats.h:37
uint32_t runtime
Definition: AP_Stats.h:17
uint32_t flttime
Definition: AP_Stats.h:16
AP_Int32 reset
Definition: AP_Stats.h:39
AP_Int16 bootcount
Definition: AP_Stats.h:36
AP_Int32 runtime
Definition: AP_Stats.h:38
uint64_t _last_runtime_ms
Definition: AP_Stats.h:48
const uint16_t flush_interval_ms
Definition: AP_Stats.h:45
void flush()
Definition: AP_Stats.cpp:60
void update()
Definition: AP_Stats.cpp:84
A system for managing and storing variables that are of general interest to the system.
struct AP_Stats::@185 params
void update_flighttime()
Definition: AP_Stats.cpp:66
uint64_t last_flush_ms
Definition: AP_Stats.h:44
void set_flying(bool b)
Definition: AP_Stats.cpp:109
uint32_t reset
Definition: AP_Stats.h:18
uint64_t _flying_ms
Definition: AP_Stats.h:47
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Stats.h:31
void init()
Definition: AP_Stats.cpp:51
Common definitions and utility routines for the ArduPilot libraries.
void copy_variables_from_parameters()
Definition: AP_Stats.cpp:44
void update_runtime()
Definition: AP_Stats.cpp:76