PerfInfo.h 1011 B

1234567891011121314151617181920212223242526272829303132333435363738394041424344
  1. #pragma once
  2. #include <stdint.h>
  3. namespace AP {
  4. class PerfInfo {
  5. public:
  6. PerfInfo() {}
  7. /* Do not allow copies */
  8. PerfInfo(const PerfInfo &other) = delete;
  9. PerfInfo &operator=(const PerfInfo&) = delete;
  10. void reset();
  11. void ignore_this_loop();
  12. void check_loop_time(uint32_t time_in_micros);
  13. uint16_t get_num_loops() const;
  14. uint32_t get_max_time() const;
  15. uint32_t get_min_time() const;
  16. uint16_t get_num_long_running() const;
  17. uint32_t get_avg_time() const;
  18. uint32_t get_stddev_time() const;
  19. float get_filtered_time() const;
  20. void set_loop_rate(uint16_t rate_hz);
  21. void update_logging();
  22. private:
  23. uint16_t loop_rate_hz;
  24. uint16_t overtime_threshold_micros;
  25. uint16_t loop_count;
  26. uint32_t max_time; // in microseconds
  27. uint32_t min_time; // in microseconds
  28. uint64_t sigma_time;
  29. uint64_t sigmasquared_time;
  30. uint16_t long_running;
  31. uint32_t last_check_us;
  32. float filtered_loop_time;
  33. bool ignore_loop;
  34. };
  35. };