Browse Source

AP_Scheduler: move PERF: statustext sending into AP_Scheduler

mission-4.1.18
Peter Barker 7 years ago committed by Andrew Tridgell
parent
commit
d151b27e92
  1. 7
      libraries/AP_Scheduler/AP_Scheduler.cpp
  2. 3
      libraries/AP_Scheduler/AP_Scheduler.h
  3. 13
      libraries/AP_Scheduler/PerfInfo.cpp
  4. 2
      libraries/AP_Scheduler/PerfInfo.h

7
libraries/AP_Scheduler/AP_Scheduler.cpp

@ -240,3 +240,10 @@ void AP_Scheduler::loop() @@ -240,3 +240,10 @@ void AP_Scheduler::loop()
#endif
perf_info.check_loop_time(AP_HAL::micros() - loop_start);
}
void AP_Scheduler::update_logging()
{
if (debug()) {
perf_info.update_logging();
}
}

3
libraries/AP_Scheduler/AP_Scheduler.h

@ -78,6 +78,9 @@ public: @@ -78,6 +78,9 @@ public:
// that function does
void loop();
// call to update any logging the scheduler might do; call at 1Hz
void update_logging();
// call when one tick has passed
void tick(void);

13
libraries/AP_Scheduler/PerfInfo.cpp

@ -1,6 +1,7 @@ @@ -1,6 +1,7 @@
#include "PerfInfo.h"
#include <DataFlash/DataFlash.h>
#include <GCS_MAVLink/GCS.h>
//
// high level performance monitoring
@ -93,3 +94,15 @@ uint32_t AP::PerfInfo::get_stddev_time() const @@ -93,3 +94,15 @@ uint32_t AP::PerfInfo::get_stddev_time() const
{
return sqrt((sigmasquared_time - (sigma_time*sigma_time)/loop_count) / loop_count);
}
void AP::PerfInfo::update_logging()
{
gcs().send_text(MAV_SEVERITY_WARNING,
"PERF: %u/%u max=%lu min=%lu avg=%lu sd=%lu",
(unsigned)get_num_long_running(),
(unsigned)get_num_loops(),
(unsigned long)get_max_time(),
(unsigned long)get_min_time(),
(unsigned long)get_avg_time(),
(unsigned long)get_stddev_time());
}

2
libraries/AP_Scheduler/PerfInfo.h

@ -28,6 +28,8 @@ public: @@ -28,6 +28,8 @@ public:
overtime_threshold_micros = 1000000/rate_hz * 1.2f;
}
void update_logging();
private:
uint16_t overtime_threshold_micros;
uint16_t loop_count;

Loading…
Cancel
Save