mirror of https://github.com/ArduPilot/ardupilot
AP_Scheduler: use also task name besides the id for logging
This makes it easier to identify for which task a log line is.
This commit is contained in:
parent
b59154103f
commit
53b5b70960
|
@ -73,8 +73,9 @@ void AP_Scheduler::run(uint16_t time_available)
|
|||
if (dt >= interval_ticks*2) {
|
||||
// we've slipped a whole run of this task!
|
||||
if (_debug > 1) {
|
||||
hal.console->printf_P(PSTR("Scheduler slip task[%u] (%u/%u/%u)\n"),
|
||||
hal.console->printf_P(PSTR("Scheduler slip task[%u-%s] (%u/%u/%u)\n"),
|
||||
(unsigned)i,
|
||||
_tasks[i].name,
|
||||
(unsigned)dt,
|
||||
(unsigned)interval_ticks,
|
||||
(unsigned)_task_time_allowed);
|
||||
|
@ -101,8 +102,9 @@ void AP_Scheduler::run(uint16_t time_available)
|
|||
if (time_taken > _task_time_allowed) {
|
||||
// the event overran!
|
||||
if (_debug > 2) {
|
||||
hal.console->printf_P(PSTR("Scheduler overrun task[%u] (%u/%u)\n"),
|
||||
hal.console->printf_P(PSTR("Scheduler overrun task[%u-%s] (%u/%u)\n"),
|
||||
(unsigned)i,
|
||||
_tasks[i].name,
|
||||
(unsigned)time_taken,
|
||||
(unsigned)_task_time_allowed);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue