mirror of https://github.com/ArduPilot/ardupilot
AP_Scheduler: adjust debug levels
this is more useful for performance analysis of scheduler, using perf command
This commit is contained in:
parent
5c62e4f4c2
commit
56aa467d60
|
@ -93,7 +93,7 @@ void AP_Scheduler::run(uint32_t time_available)
|
|||
uint32_t run_started_usec = AP_HAL::micros();
|
||||
uint32_t now = run_started_usec;
|
||||
|
||||
if (_debug > 3 && _perf_counters == nullptr) {
|
||||
if (_debug > 1 && _perf_counters == nullptr) {
|
||||
_perf_counters = new AP_HAL::Util::perf_counter_t[_num_tasks];
|
||||
if (_perf_counters != nullptr) {
|
||||
for (uint8_t i=0; i<_num_tasks; i++) {
|
||||
|
@ -114,7 +114,7 @@ void AP_Scheduler::run(uint32_t time_available)
|
|||
|
||||
if (dt >= interval_ticks*2) {
|
||||
// we've slipped a whole run of this task!
|
||||
if (_debug > 1) {
|
||||
if (_debug > 4) {
|
||||
::printf("Scheduler slip task[%u-%s] (%u/%u/%u)\n",
|
||||
(unsigned)i,
|
||||
_tasks[i].name,
|
||||
|
@ -128,11 +128,11 @@ void AP_Scheduler::run(uint32_t time_available)
|
|||
// run it
|
||||
_task_time_started = now;
|
||||
current_task = i;
|
||||
if (_debug > 3 && _perf_counters && _perf_counters[i]) {
|
||||
if (_debug > 1 && _perf_counters && _perf_counters[i]) {
|
||||
hal.util->perf_begin(_perf_counters[i]);
|
||||
}
|
||||
_tasks[i].function();
|
||||
if (_debug > 3 && _perf_counters && _perf_counters[i]) {
|
||||
if (_debug > 1 && _perf_counters && _perf_counters[i]) {
|
||||
hal.util->perf_end(_perf_counters[i]);
|
||||
}
|
||||
current_task = -1;
|
||||
|
|
Loading…
Reference in New Issue