2016-01-14 15:30:56 -04:00
|
|
|
#include "Sub.h"
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
//
|
|
|
|
// high level performance monitoring
|
|
|
|
//
|
|
|
|
// we measure the main loop time
|
|
|
|
//
|
|
|
|
|
|
|
|
// 400hz loop update rate
|
|
|
|
#define PERF_INFO_OVERTIME_THRESHOLD_MICROS 3000
|
|
|
|
|
|
|
|
static uint16_t perf_info_loop_count;
|
2017-07-15 02:37:29 -03:00
|
|
|
static uint32_t perf_info_max_time; // in microseconds
|
|
|
|
static uint32_t perf_info_min_time; // in microseconds
|
2015-12-30 18:57:56 -04:00
|
|
|
static uint16_t perf_info_long_running;
|
2016-04-21 20:06:15 -03:00
|
|
|
static uint32_t perf_info_log_dropped;
|
2015-12-30 18:57:56 -04:00
|
|
|
static bool perf_ignore_loop = false;
|
|
|
|
|
|
|
|
// perf_info_reset - reset all records of loop time to zero
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::perf_info_reset()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
perf_info_loop_count = 0;
|
|
|
|
perf_info_max_time = 0;
|
|
|
|
perf_info_min_time = 0;
|
|
|
|
perf_info_long_running = 0;
|
2016-04-21 20:06:15 -03:00
|
|
|
perf_info_log_dropped = DataFlash.num_dropped();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// perf_ignore_loop - ignore this loop from performance measurements (used to reduce false positive when arming)
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::perf_ignore_this_loop()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
perf_ignore_loop = true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// perf_info_check_loop_time - check latest loop time vs min, max and overtime threshold
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::perf_info_check_loop_time(uint32_t time_in_micros)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
perf_info_loop_count++;
|
|
|
|
|
|
|
|
// exit if this loop should be ignored
|
|
|
|
if (perf_ignore_loop) {
|
|
|
|
perf_ignore_loop = false;
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
if (time_in_micros > perf_info_max_time) {
|
2015-12-30 18:57:56 -04:00
|
|
|
perf_info_max_time = time_in_micros;
|
|
|
|
}
|
2017-02-03 17:33:27 -04:00
|
|
|
if (perf_info_min_time == 0 || time_in_micros < perf_info_min_time) {
|
2015-12-30 18:57:56 -04:00
|
|
|
perf_info_min_time = time_in_micros;
|
|
|
|
}
|
2017-02-03 17:33:27 -04:00
|
|
|
if (time_in_micros > PERF_INFO_OVERTIME_THRESHOLD_MICROS) {
|
2015-12-30 18:57:56 -04:00
|
|
|
perf_info_long_running++;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// perf_info_get_long_running_percentage - get number of long running loops as a percentage of the total number of loops
|
2016-01-14 15:30:56 -04:00
|
|
|
uint16_t Sub::perf_info_get_num_loops()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
return perf_info_loop_count;
|
|
|
|
}
|
|
|
|
|
|
|
|
// perf_info_get_max_time - return maximum loop time (in microseconds)
|
2016-01-14 15:30:56 -04:00
|
|
|
uint32_t Sub::perf_info_get_max_time()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
return perf_info_max_time;
|
|
|
|
}
|
|
|
|
|
|
|
|
// perf_info_get_max_time - return maximum loop time (in microseconds)
|
2016-01-14 15:30:56 -04:00
|
|
|
uint32_t Sub::perf_info_get_min_time()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
return perf_info_min_time;
|
|
|
|
}
|
|
|
|
|
|
|
|
// perf_info_get_num_long_running - get number of long running loops
|
2016-01-14 15:30:56 -04:00
|
|
|
uint16_t Sub::perf_info_get_num_long_running()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
return perf_info_long_running;
|
|
|
|
}
|
2016-04-21 20:06:15 -03:00
|
|
|
|
|
|
|
// perf_info_get_num_dropped - get number of dropped log messages
|
|
|
|
uint32_t Sub::perf_info_get_num_dropped()
|
|
|
|
{
|
|
|
|
return perf_info_log_dropped;
|
|
|
|
}
|