PerfInfo.cpp 3.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137
  1. #include "PerfInfo.h"
  2. #include <AP_Logger/AP_Logger.h>
  3. #include <GCS_MAVLink/GCS.h>
  4. #include "AP_Scheduler.h"
  5. extern const AP_HAL::HAL& hal;
  6. //
  7. // high level performance monitoring
  8. //
  9. // we measure the main loop time
  10. //
  11. // reset - reset all records of loop time to zero
  12. void AP::PerfInfo::reset()
  13. {
  14. loop_count = 0;
  15. max_time = 0;
  16. min_time = 0;
  17. long_running = 0;
  18. sigma_time = 0;
  19. sigmasquared_time = 0;
  20. }
  21. // ignore_loop - ignore this loop from performance measurements (used to reduce false positive when arming)
  22. void AP::PerfInfo::ignore_this_loop()
  23. {
  24. ignore_loop = true;
  25. }
  26. // check_loop_time - check latest loop time vs min, max and overtime threshold
  27. void AP::PerfInfo::check_loop_time(uint32_t time_in_micros)
  28. {
  29. loop_count++;
  30. // exit if this loop should be ignored
  31. if (ignore_loop) {
  32. ignore_loop = false;
  33. return;
  34. }
  35. if( time_in_micros > max_time) {
  36. max_time = time_in_micros;
  37. }
  38. if( min_time == 0 || time_in_micros < min_time) {
  39. min_time = time_in_micros;
  40. }
  41. if (time_in_micros > overtime_threshold_micros) {
  42. long_running++;
  43. }
  44. sigma_time += time_in_micros;
  45. sigmasquared_time += time_in_micros * time_in_micros;
  46. /* we keep a filtered loop time for use as G_Dt which is the
  47. predicted time for the next loop. We remove really excessive
  48. times from this calculation so as not to throw it off too far
  49. in case we get a single long loop
  50. Note that the time we use here is the time between calls to
  51. check_loop_time() not the time from loop start to loop
  52. end. This is because we are using the time for time between
  53. calls to controllers, which has nothing to do with cpu speed.
  54. */
  55. const uint32_t now = AP_HAL::micros();
  56. const uint32_t loop_time_us = now - last_check_us;
  57. last_check_us = now;
  58. if (loop_time_us < overtime_threshold_micros + 10000UL) {
  59. filtered_loop_time = 0.99f * filtered_loop_time + 0.01f * loop_time_us * 1.0e-6f;
  60. }
  61. }
  62. // get_num_loops: return number of loops used for recording performance
  63. uint16_t AP::PerfInfo::get_num_loops() const
  64. {
  65. return loop_count;
  66. }
  67. // get_max_time - return maximum loop time (in microseconds)
  68. uint32_t AP::PerfInfo::get_max_time() const
  69. {
  70. return max_time;
  71. }
  72. // get_min_time - return minumum loop time (in microseconds)
  73. uint32_t AP::PerfInfo::get_min_time() const
  74. {
  75. return min_time;
  76. }
  77. // get_num_long_running - get number of long running loops
  78. uint16_t AP::PerfInfo::get_num_long_running() const
  79. {
  80. return long_running;
  81. }
  82. // get_avg_time - return average loop time (in microseconds)
  83. uint32_t AP::PerfInfo::get_avg_time() const
  84. {
  85. return (sigma_time / loop_count);
  86. }
  87. // get_stddev_time - return stddev of average loop time (in us)
  88. uint32_t AP::PerfInfo::get_stddev_time() const
  89. {
  90. return sqrtf((sigmasquared_time - (sigma_time*sigma_time)/loop_count) / loop_count);
  91. }
  92. // get_filtered_time - return low pass filtered loop time in seconds
  93. float AP::PerfInfo::get_filtered_time() const
  94. {
  95. return filtered_loop_time;
  96. }
  97. void AP::PerfInfo::update_logging()
  98. {
  99. gcs().send_text(MAV_SEVERITY_WARNING,
  100. "PERF: %u/%u [%lu:%lu] F=%uHz sd=%lu Ex=%lu",
  101. (unsigned)get_num_long_running(),
  102. (unsigned)get_num_loops(),
  103. (unsigned long)get_max_time(),
  104. (unsigned long)get_min_time(),
  105. (unsigned)(0.5+(1.0f/get_filtered_time())),
  106. (unsigned long)get_stddev_time(),
  107. (unsigned long)AP::scheduler().get_extra_loop_us());
  108. }
  109. void AP::PerfInfo::set_loop_rate(uint16_t rate_hz)
  110. {
  111. // allow a 20% overrun before we consider a loop "slow":
  112. overtime_threshold_micros = 1000000/rate_hz * 1.2f;
  113. if (loop_rate_hz != rate_hz) {
  114. loop_rate_hz = rate_hz;
  115. filtered_loop_time = 1.0f / rate_hz;
  116. }
  117. }