APM:Libraries
PerfInfo.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <stdint.h>
4 
5 namespace AP {
6 
7 class PerfInfo {
8 public:
9  PerfInfo() {}
10 
11  /* Do not allow copies */
12  PerfInfo(const PerfInfo &other) = delete;
13  PerfInfo &operator=(const PerfInfo&) = delete;
14 
15  void reset();
16  void ignore_this_loop();
17  void check_loop_time(uint32_t time_in_micros);
18  uint16_t get_num_loops() const;
19  uint32_t get_max_time() const;
20  uint32_t get_min_time() const;
21  uint16_t get_num_long_running() const;
22  uint32_t get_avg_time() const;
23  uint32_t get_stddev_time() const;
24  float get_filtered_time() const;
25  void set_loop_rate(uint16_t rate_hz);
26 
27  void update_logging();
28 
29 private:
30  uint16_t loop_rate_hz;
32  uint16_t loop_count;
33  uint32_t max_time; // in microseconds
34  uint32_t min_time; // in microseconds
35  uint64_t sigma_time;
37  uint16_t long_running;
38  uint32_t last_check_us;
41 
42 };
43 
44 };
float filtered_loop_time
Definition: PerfInfo.h:39
uint16_t loop_rate_hz
Definition: PerfInfo.h:30
uint16_t get_num_loops() const
Definition: PerfInfo.cpp:73
float get_filtered_time() const
Definition: PerfInfo.cpp:109
uint16_t loop_count
Definition: PerfInfo.h:32
uint32_t last_check_us
Definition: PerfInfo.h:38
void ignore_this_loop()
Definition: PerfInfo.cpp:26
uint32_t min_time
Definition: PerfInfo.h:34
Definition: AP_AHRS.cpp:486
void check_loop_time(uint32_t time_in_micros)
Definition: PerfInfo.cpp:32
void set_loop_rate(uint16_t rate_hz)
Definition: PerfInfo.cpp:126
void update_logging()
Definition: PerfInfo.cpp:114
uint32_t get_avg_time() const
Definition: PerfInfo.cpp:97
uint32_t get_stddev_time() const
Definition: PerfInfo.cpp:103
uint16_t overtime_threshold_micros
Definition: PerfInfo.h:31
uint64_t sigmasquared_time
Definition: PerfInfo.h:36
PerfInfo & operator=(const PerfInfo &)=delete
uint32_t get_min_time() const
Definition: PerfInfo.cpp:85
uint32_t max_time
Definition: PerfInfo.h:33
uint32_t get_max_time() const
Definition: PerfInfo.cpp:79
uint16_t get_num_long_running() const
Definition: PerfInfo.cpp:91
uint64_t sigma_time
Definition: PerfInfo.h:35
uint16_t long_running
Definition: PerfInfo.h:37
bool ignore_loop
Definition: PerfInfo.h:40
void reset()
Definition: PerfInfo.cpp:15