Browse Source

AP_Scheduler: PerfInfo: allow specification of loop rate

master
Peter Barker 7 years ago committed by Andrew Tridgell
parent
commit
ae9d4d514d
  1. 7
      libraries/AP_Scheduler/PerfInfo.h

7
libraries/AP_Scheduler/PerfInfo.h

@ -23,7 +23,13 @@ public: @@ -23,7 +23,13 @@ public:
uint32_t get_avg_time() const;
uint32_t get_stddev_time() const;
void set_loop_rate(uint16_t rate_hz) {
// allow a 20% overrun before we consider a loop "slow":
overtime_threshold_micros = 1000000/rate_hz * 1.2f;
}
private:
uint16_t overtime_threshold_micros;
uint16_t loop_count;
uint32_t max_time; // in microseconds
uint32_t min_time; // in microseconds
@ -33,6 +39,7 @@ private: @@ -33,6 +39,7 @@ private:
uint32_t log_dropped;
uint32_t overtime_threshold_us;
bool ignore_loop;
};
};

Loading…
Cancel
Save