APM:Libraries
PerfInfo.cpp
Go to the documentation of this file.
1 #include "PerfInfo.h"
2 
3 #include <DataFlash/DataFlash.h>
4 #include <GCS_MAVLink/GCS.h>
5 
6 extern const AP_HAL::HAL& hal;
7 
8 //
9 // high level performance monitoring
10 //
11 // we measure the main loop time
12 //
13 
14 // reset - reset all records of loop time to zero
16 {
17  loop_count = 0;
18  max_time = 0;
19  min_time = 0;
20  long_running = 0;
21  sigma_time = 0;
23 }
24 
25 // ignore_loop - ignore this loop from performance measurements (used to reduce false positive when arming)
27 {
28  ignore_loop = true;
29 }
30 
31 // check_loop_time - check latest loop time vs min, max and overtime threshold
32 void AP::PerfInfo::check_loop_time(uint32_t time_in_micros)
33 {
34  loop_count++;
35 
36  // exit if this loop should be ignored
37  if (ignore_loop) {
38  ignore_loop = false;
39  return;
40  }
41 
42  if( time_in_micros > max_time) {
43  max_time = time_in_micros;
44  }
45  if( min_time == 0 || time_in_micros < min_time) {
46  min_time = time_in_micros;
47  }
48  if (time_in_micros > overtime_threshold_micros) {
49  long_running++;
50  }
51  sigma_time += time_in_micros;
52  sigmasquared_time += time_in_micros * time_in_micros;
53 
54  /* we keep a filtered loop time for use as G_Dt which is the
55  predicted time for the next loop. We remove really excessive
56  times from this calculation so as not to throw it off too far
57  in case we get a single long loop
58 
59  Note that the time we use here is the time between calls to
60  check_loop_time() not the time from loop start to loop
61  end. This is because we are using the time for time between
62  calls to controllers, which has nothing to do with cpu speed.
63  */
64  const uint32_t now = AP_HAL::micros();
65  const uint32_t loop_time_us = now - last_check_us;
66  last_check_us = now;
67  if (loop_time_us < overtime_threshold_micros + 10000UL) {
68  filtered_loop_time = 0.99f * filtered_loop_time + 0.01f * loop_time_us * 1.0e-6f;
69  }
70 }
71 
72 // get_num_loops: return number of loops used for recording performance
74 {
75  return loop_count;
76 }
77 
78 // get_max_time - return maximum loop time (in microseconds)
80 {
81  return max_time;
82 }
83 
84 // get_min_time - return minumum loop time (in microseconds)
86 {
87  return min_time;
88 }
89 
90 // get_num_long_running - get number of long running loops
92 {
93  return long_running;
94 }
95 
96 // get_avg_time - return average loop time (in microseconds)
98 {
99  return (sigma_time / loop_count);
100 }
101 
102 // get_stddev_time - return stddev of average loop time (in us)
104 {
106 }
107 
108 // get_filtered_time - return low pass filtered loop time in seconds
110 {
111  return filtered_loop_time;
112 }
113 
115 {
116  gcs().send_text(MAV_SEVERITY_WARNING,
117  "PERF: %u/%u max=%lu min=%lu F=%u sd=%lu",
118  (unsigned)get_num_long_running(),
119  (unsigned)get_num_loops(),
120  (unsigned long)get_max_time(),
121  (unsigned long)get_min_time(),
122  (unsigned)(get_filtered_time()*1.0e6),
123  (unsigned long)get_stddev_time());
124 }
125 
126 void AP::PerfInfo::set_loop_rate(uint16_t rate_hz)
127 {
128  // allow a 20% overrun before we consider a loop "slow":
129  overtime_threshold_micros = 1000000/rate_hz * 1.2f;
130 
131  if (loop_rate_hz != rate_hz) {
132  loop_rate_hz = rate_hz;
133  filtered_loop_time = 1.0f / rate_hz;
134  }
135 }
float filtered_loop_time
Definition: PerfInfo.h:39
uint16_t loop_rate_hz
Definition: PerfInfo.h:30
Interface definition for the various Ground Control System.
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
GCS & gcs()
uint32_t min_time
Definition: PerfInfo.h:34
void check_loop_time(uint32_t time_in_micros)
Definition: PerfInfo.cpp:32
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define f(i)
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
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
uint16_t overtime_threshold_micros
Definition: PerfInfo.h:31
uint64_t sigmasquared_time
Definition: PerfInfo.h:36
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
uint32_t micros()
Definition: system.cpp:152