Browse Source

AP_Scheduler: scale perf_info with loop rate

this allows it to be used for a wide range of loop rates
master
Andrew Tridgell 7 years ago
parent
commit
b3ed8fd3f9
  1. 9
      libraries/AP_Scheduler/PerfInfo.cpp
  2. 3
      libraries/AP_Scheduler/PerfInfo.h

9
libraries/AP_Scheduler/PerfInfo.cpp

@ -8,11 +8,8 @@
// we measure the main loop time // we measure the main loop time
// //
// 400hz loop update rate
#define OVERTIME_THRESHOLD_MICROS 3000
// reset - reset all records of loop time to zero // reset - reset all records of loop time to zero
void AP::PerfInfo::reset() void AP::PerfInfo::reset(uint16_t loop_rate_hz)
{ {
loop_count = 0; loop_count = 0;
max_time = 0; max_time = 0;
@ -21,6 +18,8 @@ void AP::PerfInfo::reset()
log_dropped = DataFlash_Class::instance()->num_dropped(); log_dropped = DataFlash_Class::instance()->num_dropped();
sigma_time = 0; sigma_time = 0;
sigmasquared_time = 0; sigmasquared_time = 0;
// 500us threshold for overtime
overtime_threshold_us = (1000000UL / loop_rate_hz) + 500;
} }
// ignore_loop - ignore this loop from performance measurements (used to reduce false positive when arming) // ignore_loop - ignore this loop from performance measurements (used to reduce false positive when arming)
@ -46,7 +45,7 @@ void AP::PerfInfo::check_loop_time(uint32_t time_in_micros)
if( min_time == 0 || time_in_micros < min_time) { if( min_time == 0 || time_in_micros < min_time) {
min_time = time_in_micros; min_time = time_in_micros;
} }
if( time_in_micros > OVERTIME_THRESHOLD_MICROS ) { if (time_in_micros > overtime_threshold_us) {
long_running++; long_running++;
} }
sigma_time += time_in_micros; sigma_time += time_in_micros;

3
libraries/AP_Scheduler/PerfInfo.h

@ -10,7 +10,7 @@ public:
PerfInfo(const PerfInfo &other) = delete; PerfInfo(const PerfInfo &other) = delete;
PerfInfo &operator=(const PerfInfo&) = delete; PerfInfo &operator=(const PerfInfo&) = delete;
void reset(); void reset(uint16_t loop_rate_hz);
void ignore_this_loop(); void ignore_this_loop();
void check_loop_time(uint32_t time_in_micros); void check_loop_time(uint32_t time_in_micros);
uint16_t get_num_loops() const; uint16_t get_num_loops() const;
@ -29,6 +29,7 @@ private:
uint64_t sigmasquared_time; uint64_t sigmasquared_time;
uint16_t long_running; uint16_t long_running;
uint32_t log_dropped; uint32_t log_dropped;
uint32_t overtime_threshold_us;
bool ignore_loop; bool ignore_loop;
}; };

Loading…
Cancel
Save