APM:Libraries
Perf.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016 Intel Corporation. All rights reserved.
3  *
4  * This file is free software: you can redistribute it and/or modify it
5  * under the terms of the GNU General Public License as published by the
6  * Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * This file is distributed in the hope that it will be useful, but
10  * WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
12  * See the GNU General Public License for more details.
13  *
14  * You should have received a copy of the GNU General Public License along
15  * with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 #include <inttypes.h>
18 #include <stdio.h>
19 #include <time.h>
20 #include <vector>
21 
22 #include <AP_HAL/AP_HAL.h>
23 #include <AP_Math/AP_Math.h>
24 
25 #include "AP_HAL_Linux.h"
26 #include "Util.h"
27 #include "Perf.h"
28 #include "Perf_Lttng.h"
29 
30 #ifndef PRIu64
31 #define PRIu64 "llu"
32 #endif
33 
34 using namespace Linux;
35 
36 static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
37 
39 
40 static inline uint64_t now_nsec()
41 {
42  struct timespec ts;
43  clock_gettime(CLOCK_MONOTONIC, &ts);
44  return ts.tv_nsec + (ts.tv_sec * AP_NSEC_PER_SEC);
45 }
46 
48 {
49  if (!_instance) {
50  _instance = new Perf();
51  }
52 
53  return _instance;
54 }
55 
57 {
58  uint64_t now = AP_HAL::millis64();
59 
60  if (now - _last_debug_msec < 5000) {
61  return;
62  }
63 
64  pthread_rwlock_rdlock(&_perf_counters_lock);
65  unsigned int uc = _update_count;
66  auto v = _perf_counters;
67  pthread_rwlock_unlock(&_perf_counters_lock);
68 
69  if (uc != _update_count) {
70  fprintf(stderr, "WARNING!! potentially wrong counters!!!");
71  }
72 
73  for (auto &c : v) {
74  if (!c.count) {
75  fprintf(stderr, "%-30s\t"
76  "(no events)\n", c.name);
77  } else if (c.type == Util::PC_ELAPSED) {
78  fprintf(stderr, "%-30s\t"
79  "count: %" PRIu64 "\t"
80  "min: %" PRIu64 "\t"
81  "max: %" PRIu64 "\t"
82  "avg: %.4f\t"
83  "stddev: %.4f\n",
84  c.name, c.count, c.min, c.max, c.avg, sqrt(c.m2));
85  } else {
86  fprintf(stderr, "%-30s\t"
87  "count: %" PRIu64 "\n",
88  c.name, c.count);
89  }
90  }
91 
92  _last_debug_msec = now;
93 }
94 
96 {
97  if (pthread_rwlock_init(&_perf_counters_lock, nullptr) != 0) {
98  AP_HAL::panic("Perf: fail to initialize rw lock");
99  }
100 
101  /* TODO: this number should come from vehicle code - just estimate the
102  * number of perf counters for now; if we grow more, it will just
103  * reallocate the memory pool */
104  _perf_counters.reserve(50);
105 
106 #ifdef DEBUG_PERF
108 #endif
109 }
110 
112 {
113  uintptr_t idx = (uintptr_t)pc;
114 
115  if (idx >= _perf_counters.size()) {
116  return;
117  }
118 
119  Perf_Counter &perf = _perf_counters[idx];
120  if (perf.type != Util::PC_ELAPSED) {
121  hal.console->printf("perf_begin() called on perf_counter_t(%s) that"
122  " is not of PC_ELAPSED type.\n",
123  perf.name);
124  return;
125  }
126 
127  if (perf.start != 0) {
128  hal.console->printf("perf_begin() called twice on perf_counter_t(%s)\n",
129  perf.name);
130  return;
131  }
132 
133  _update_count++;
134 
135  perf.start = now_nsec();
136 
137  perf.lttng.begin(perf.name);
138 }
139 
141 {
142  uintptr_t idx = (uintptr_t)pc;
143 
144  if (idx >= _perf_counters.size()) {
145  return;
146  }
147 
148  Perf_Counter &perf = _perf_counters[idx];
149  if (perf.type != Util::PC_ELAPSED) {
150  hal.console->printf("perf_begin() called on perf_counter_t(%s) that"
151  " is not of PC_ELAPSED type.\n",
152  perf.name);
153  return;
154  }
155 
156  if (perf.start == 0) {
157  hal.console->printf("perf_begin() called before begin() on perf_counter_t(%s)\n",
158  perf.name);
159  return;
160  }
161 
162  _update_count++;
163 
164  const uint64_t elapsed = now_nsec() - perf.start;
165  perf.count++;
166  perf.total += elapsed;
167 
168  if (perf.min > elapsed) {
169  perf.min = elapsed;
170  }
171 
172  if (perf.max < elapsed) {
173  perf.max = elapsed;
174  }
175 
176  /*
177  * Maintain avg and variance of interval in nanoseconds
178  * Knuth/Welford recursive avg and variance of update intervals (via Wikipedia)
179  * Same implementation of PX4.
180  */
181  const double delta_intvl = elapsed - perf.avg;
182  perf.avg += (delta_intvl / perf.count);
183  perf.m2 += (delta_intvl * (elapsed - perf.avg));
184  perf.start = 0;
185 
186  perf.lttng.end(perf.name);
187 }
188 
190 {
191  uintptr_t idx = (uintptr_t)pc;
192 
193  if (idx >= _perf_counters.size()) {
194  return;
195  }
196 
197  Perf_Counter &perf = _perf_counters[idx];
198  if (perf.type != Util::PC_COUNT) {
199  hal.console->printf("perf_begin() called on perf_counter_t(%s) that"
200  " is not of PC_COUNT type.\n",
201  perf.name);
202  return;
203  }
204 
205  _update_count++;
206  perf.count++;
207 
208  perf.lttng.count(perf.name, perf.count);
209 }
210 
212 {
213  if (type != Util::PC_COUNT && type != Util::PC_ELAPSED) {
214  /*
215  * Other perf counters not implemented for now since they are not
216  * used anywhere.
217  */
218  return (Util::perf_counter_t)(uintptr_t) -1;
219  }
220 
221  pthread_rwlock_wrlock(&_perf_counters_lock);
223  _perf_counters.emplace_back(type, name);
224  pthread_rwlock_unlock(&_perf_counters_lock);
225 
226  return pc;
227 }
#define PRIu64
Definition: Perf.cpp:31
void end(perf_counter_t pc)
Definition: Perf.cpp:140
void clock_gettime(uint32_t a1, void *a2)
Definition: syscalls.c:201
void _debug_counters()
Definition: Perf.cpp:56
std::vector< Perf_Counter > _perf_counters
Definition: Perf.h:86
uint64_t min
Definition: Perf.h:53
AP_HAL::UARTDriver * console
Definition: HAL.h:110
uint64_t max
Definition: Perf.h:54
uint64_t count
Definition: Perf.h:48
void begin(perf_counter_t pc)
Definition: Perf.cpp:111
std::atomic< unsigned int > _update_count
Definition: Perf.h:92
perf_counter_type type
Definition: Perf.h:46
pthread_rwlock_t _perf_counters_lock
Definition: Perf.h:89
const char * name
Definition: BusTest.cpp:11
uint64_t millis64()
Definition: system.cpp:167
uint64_t start
Definition: Perf.h:51
Perf_Lttng lttng
Definition: Perf.h:44
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
void end(const char *name)
Definition: Perf_Lttng.cpp:50
const char * name
Definition: Perf.h:43
void * perf_counter_t
Definition: Util.h:101
#define AP_NSEC_PER_SEC
Definition: definitions.h:90
perf_counter_type
Definition: Util.h:96
static const AP_HAL::HAL & hal
Definition: I2CDevice.cpp:61
float v
Definition: Printf.cpp:15
uint64_t total
Definition: Perf.h:52
const HAL & get_HAL()
perf_counter_t add(perf_counter_type type, const char *name)
Definition: Perf.cpp:211
static Perf * _instance
Definition: Perf.h:78
virtual void register_timer_process(AP_HAL::MemberProc)=0
void count(perf_counter_t pc)
Definition: Perf.cpp:189
uint64_t _last_debug_msec
Definition: Perf.h:84
void begin(const char *name)
Definition: Perf_Lttng.cpp:49
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
static Perf * get_instance()
Definition: Perf.cpp:47
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
static uint64_t now_nsec()
Definition: Perf.cpp:40
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
double avg
Definition: Perf.h:56
void count(const char *name, uint64_t val)
Definition: Perf_Lttng.cpp:51