mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Sub: add average and stddev time to SCHED_DEBUG output
This commit is contained in:
parent
901dc46708
commit
fc3721c123
@ -108,11 +108,13 @@ void Sub::perf_update(void)
|
||||
Log_Write_Performance();
|
||||
}
|
||||
if (scheduler.debug()) {
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "PERF: %u/%u %lu %lu",
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "PERF: %u/%u max=%lu min=%lu avg=%lu sd=%lu",
|
||||
(unsigned)perf_info.get_num_long_running(),
|
||||
(unsigned)perf_info.get_num_loops(),
|
||||
(unsigned long)perf_info.get_max_time(),
|
||||
(unsigned long)perf_info.get_min_time());
|
||||
(unsigned long)perf_info.get_min_time(),
|
||||
(unsigned long)perf_info.get_avg_time(),
|
||||
(unsigned long)perf_info.get_stddev_time());
|
||||
}
|
||||
perf_info.reset();
|
||||
pmTest1 = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user