AP_Scheduler: add and use AP_SCHEDULER_EXTENDED_TASKINFO_ENABLED

This commit is contained in:
Peter Barker 2023-06-15 19:55:49 +10:00 committed by Andrew Tridgell
parent 6e39565ce8
commit 8b13413f43
3 changed files with 11 additions and 7 deletions

View File

@ -28,12 +28,12 @@
#include <AP_Math/AP_Math.h>
#include "PerfInfo.h" // loop perf monitoring
#if HAL_MINIMIZE_FEATURES
#define AP_SCHEDULER_NAME_INITIALIZER(_clazz,_name) .name = #_name,
#define AP_FAST_NAME_INITIALIZER(_clazz,_name) .name = #_name "*",
#else
#if AP_SCHEDULER_EXTENDED_TASKINFO_ENABLED
#define AP_SCHEDULER_NAME_INITIALIZER(_clazz,_name) .name = #_clazz "::" #_name,
#define AP_FAST_NAME_INITIALIZER(_clazz,_name) .name = #_clazz "::" #_name "*",
#else
#define AP_SCHEDULER_NAME_INITIALIZER(_clazz,_name) .name = #_name,
#define AP_FAST_NAME_INITIALIZER(_clazz,_name) .name = #_name "*",
#endif
#define LOOP_RATE 0

View File

@ -5,3 +5,7 @@
#ifndef AP_SCHEDULER_ENABLED
#define AP_SCHEDULER_ENABLED 1
#endif
#ifndef AP_SCHEDULER_EXTENDED_TASKINFO_ENABLED
#define AP_SCHEDULER_EXTENDED_TASKINFO_ENABLED 1
#endif

View File

@ -90,10 +90,10 @@ void AP::PerfInfo::TaskInfo::print(const char* task_name, uint32_t total_time, E
pct = elapsed_time_us * 100.0f / total_time;
avg = MIN(uint16_t(elapsed_time_us / tick_count), 9999);
}
#if HAL_MINIMIZE_FEATURES
const char* fmt = "%-16.16s MIN=%4u MAX=%4u AVG=%4u OVR=%3u SLP=%3u, TOT=%4.1f%%\n";
#else
#if AP_SCHEDULER_EXTENDED_TASKINFO_ENABLED
const char* fmt = "%-32.32s MIN=%4u MAX=%4u AVG=%4u OVR=%3u SLP=%3u, TOT=%4.1f%%\n";
#else
const char* fmt = "%-16.16s MIN=%4u MAX=%4u AVG=%4u OVR=%3u SLP=%3u, TOT=%4.1f%%\n";
#endif
str.printf(fmt, task_name,
unsigned(MIN(min_time_us, 9999)), unsigned(MIN(max_time_us, 9999)), unsigned(avg),