mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_Scheduler: create AP::PerfInfo class
This commit is contained in:
parent
5c2f68e8f5
commit
fd543fce6d
@ -1,4 +1,6 @@
|
||||
#include "Copter.h"
|
||||
#include "PerfInfo.h"
|
||||
|
||||
#include <DataFlash/DataFlash.h>
|
||||
|
||||
//
|
||||
// high level performance monitoring
|
||||
@ -7,97 +9,88 @@
|
||||
//
|
||||
|
||||
// 400hz loop update rate
|
||||
#define PERF_INFO_OVERTIME_THRESHOLD_MICROS 3000
|
||||
#define OVERTIME_THRESHOLD_MICROS 3000
|
||||
|
||||
static uint16_t perf_info_loop_count;
|
||||
static uint32_t perf_info_max_time; // in microseconds
|
||||
static uint32_t perf_info_min_time; // in microseconds
|
||||
static uint64_t perf_info_sigma_time;
|
||||
static uint64_t perf_info_sigmasquared_time;
|
||||
static uint16_t perf_info_long_running;
|
||||
static uint32_t perf_info_log_dropped;
|
||||
static bool perf_ignore_loop = false;
|
||||
|
||||
// perf_info_reset - reset all records of loop time to zero
|
||||
void Copter::perf_info_reset()
|
||||
// reset - reset all records of loop time to zero
|
||||
void AP::PerfInfo::reset()
|
||||
{
|
||||
perf_info_loop_count = 0;
|
||||
perf_info_max_time = 0;
|
||||
perf_info_min_time = 0;
|
||||
perf_info_long_running = 0;
|
||||
perf_info_log_dropped = DataFlash.num_dropped();
|
||||
perf_info_sigma_time = 0;
|
||||
perf_info_sigmasquared_time = 0;
|
||||
loop_count = 0;
|
||||
max_time = 0;
|
||||
min_time = 0;
|
||||
long_running = 0;
|
||||
log_dropped = DataFlash_Class::instance()->num_dropped();
|
||||
sigma_time = 0;
|
||||
sigmasquared_time = 0;
|
||||
}
|
||||
|
||||
// perf_ignore_loop - ignore this loop from performance measurements (used to reduce false positive when arming)
|
||||
void Copter::perf_ignore_this_loop()
|
||||
// ignore_loop - ignore this loop from performance measurements (used to reduce false positive when arming)
|
||||
void AP::PerfInfo::ignore_this_loop()
|
||||
{
|
||||
perf_ignore_loop = true;
|
||||
ignore_loop = true;
|
||||
}
|
||||
|
||||
// perf_info_check_loop_time - check latest loop time vs min, max and overtime threshold
|
||||
void Copter::perf_info_check_loop_time(uint32_t time_in_micros)
|
||||
// check_loop_time - check latest loop time vs min, max and overtime threshold
|
||||
void AP::PerfInfo::check_loop_time(uint32_t time_in_micros)
|
||||
{
|
||||
perf_info_loop_count++;
|
||||
loop_count++;
|
||||
|
||||
// exit if this loop should be ignored
|
||||
if (perf_ignore_loop) {
|
||||
perf_ignore_loop = false;
|
||||
if (ignore_loop) {
|
||||
ignore_loop = false;
|
||||
return;
|
||||
}
|
||||
|
||||
if( time_in_micros > perf_info_max_time) {
|
||||
perf_info_max_time = time_in_micros;
|
||||
if( time_in_micros > max_time) {
|
||||
max_time = time_in_micros;
|
||||
}
|
||||
if( perf_info_min_time == 0 || time_in_micros < perf_info_min_time) {
|
||||
perf_info_min_time = time_in_micros;
|
||||
if( min_time == 0 || time_in_micros < min_time) {
|
||||
min_time = time_in_micros;
|
||||
}
|
||||
if( time_in_micros > PERF_INFO_OVERTIME_THRESHOLD_MICROS ) {
|
||||
perf_info_long_running++;
|
||||
if( time_in_micros > OVERTIME_THRESHOLD_MICROS ) {
|
||||
long_running++;
|
||||
}
|
||||
perf_info_sigma_time += time_in_micros;
|
||||
perf_info_sigmasquared_time += time_in_micros * time_in_micros;
|
||||
sigma_time += time_in_micros;
|
||||
sigmasquared_time += time_in_micros * time_in_micros;
|
||||
}
|
||||
|
||||
// perf_info_get_long_running_percentage - get number of long running loops as a percentage of the total number of loops
|
||||
uint16_t Copter::perf_info_get_num_loops()
|
||||
// get_num_loops: return number of loops used for recording performance
|
||||
uint16_t AP::PerfInfo::get_num_loops() const
|
||||
{
|
||||
return perf_info_loop_count;
|
||||
return loop_count;
|
||||
}
|
||||
|
||||
// perf_info_get_max_time - return maximum loop time (in microseconds)
|
||||
uint32_t Copter::perf_info_get_max_time()
|
||||
// get_max_time - return maximum loop time (in microseconds)
|
||||
uint32_t AP::PerfInfo::get_max_time() const
|
||||
{
|
||||
return perf_info_max_time;
|
||||
return max_time;
|
||||
}
|
||||
|
||||
// perf_info_get_max_time - return maximum loop time (in microseconds)
|
||||
uint32_t Copter::perf_info_get_min_time()
|
||||
// get_min_time - return minumum loop time (in microseconds)
|
||||
uint32_t AP::PerfInfo::get_min_time() const
|
||||
{
|
||||
return perf_info_min_time;
|
||||
return min_time;
|
||||
}
|
||||
|
||||
// perf_info_get_num_long_running - get number of long running loops
|
||||
uint16_t Copter::perf_info_get_num_long_running()
|
||||
// get_num_long_running - get number of long running loops
|
||||
uint16_t AP::PerfInfo::get_num_long_running() const
|
||||
{
|
||||
return perf_info_long_running;
|
||||
return long_running;
|
||||
}
|
||||
|
||||
// perf_info_get_num_dropped - get number of dropped log messages
|
||||
uint32_t Copter::perf_info_get_num_dropped()
|
||||
// get_num_dropped - get number of dropped log messages
|
||||
uint32_t AP::PerfInfo::get_num_dropped() const
|
||||
{
|
||||
return perf_info_log_dropped;
|
||||
return log_dropped;
|
||||
}
|
||||
|
||||
// perf_info_get_avg_time - return average loop time (in microseconds)
|
||||
uint32_t Copter::perf_info_get_avg_time()
|
||||
// get_avg_time - return average loop time (in microseconds)
|
||||
uint32_t AP::PerfInfo::get_avg_time() const
|
||||
{
|
||||
return (perf_info_sigma_time / perf_info_loop_count);
|
||||
return (sigma_time / loop_count);
|
||||
}
|
||||
|
||||
// perf_info_get_stddev_time - return stddev of average loop time (in us)
|
||||
uint32_t Copter::perf_info_get_stddev_time()
|
||||
// get_stddev_time - return stddev of average loop time (in us)
|
||||
uint32_t AP::PerfInfo::get_stddev_time() const
|
||||
{
|
||||
return sqrt((perf_info_sigmasquared_time - (perf_info_sigma_time*perf_info_sigma_time)/perf_info_loop_count) / perf_info_loop_count);
|
||||
return sqrt((sigmasquared_time - (sigma_time*sigma_time)/loop_count) / loop_count);
|
||||
}
|
||||
|
41
libraries/AP_Scheduler/PerfInfo.h
Normal file
41
libraries/AP_Scheduler/PerfInfo.h
Normal file
@ -0,0 +1,41 @@
|
||||
#include <stdint.h>
|
||||
|
||||
namespace AP {
|
||||
|
||||
class PerfInfo {
|
||||
public:
|
||||
|
||||
static PerfInfo create() { return PerfInfo{}; }
|
||||
|
||||
constexpr PerfInfo(PerfInfo &&other) = default;
|
||||
|
||||
/* Do not allow copies */
|
||||
PerfInfo(const PerfInfo &other) = delete;
|
||||
PerfInfo &operator=(const PerfInfo&) = delete;
|
||||
|
||||
void reset();
|
||||
void ignore_this_loop();
|
||||
void check_loop_time(uint32_t time_in_micros);
|
||||
uint16_t get_num_loops() const;
|
||||
uint32_t get_max_time() const;
|
||||
uint32_t get_min_time() const;
|
||||
uint16_t get_num_long_running() const;
|
||||
uint32_t get_num_dropped() const;
|
||||
uint32_t get_avg_time() const;
|
||||
uint32_t get_stddev_time() const;
|
||||
|
||||
private:
|
||||
|
||||
PerfInfo() {}
|
||||
|
||||
uint16_t loop_count;
|
||||
uint32_t max_time; // in microseconds
|
||||
uint32_t min_time; // in microseconds
|
||||
uint64_t sigma_time;
|
||||
uint64_t sigmasquared_time;
|
||||
uint16_t long_running;
|
||||
uint32_t log_dropped;
|
||||
bool ignore_loop;
|
||||
};
|
||||
|
||||
};
|
Loading…
Reference in New Issue
Block a user