mirror of https://github.com/ArduPilot/ardupilot
AP_Scheduler: added SCHED_DEBUG=2
used to show overruns and slips
This commit is contained in:
parent
e446f375a7
commit
c437900a49
|
@ -20,7 +20,7 @@ const AP_Param::GroupInfo AP_Scheduler::var_info[] PROGMEM = {
|
|||
// @Param: DEBUG
|
||||
// @DisplayName: Scheduler debug level
|
||||
// @Description: Set to non-zero to enable scheduler debug messages
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @Values: 0:Disabled,1:ShowSlipe,2:ShowOverruns
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("DEBUG", 0, AP_Scheduler, _debug, 0),
|
||||
AP_GROUPEND
|
||||
|
@ -80,7 +80,7 @@ void AP_Scheduler::run(uint16_t time_available)
|
|||
|
||||
if (time_taken > _task_time_allowed) {
|
||||
// the event overran!
|
||||
if (_debug != 0) {
|
||||
if (_debug > 1) {
|
||||
hal.console->printf_P(PSTR("Scheduler overrun task[%u] (%u/%u)\n"),
|
||||
(unsigned)i,
|
||||
(unsigned)time_taken,
|
||||
|
|
Loading…
Reference in New Issue