mirror of https://github.com/ArduPilot/ardupilot
HAL_PX4: disable "Overtime in task" msg
this hasn't helped us find any bugs and it is very annoying with nsh over MAVLink
This commit is contained in:
parent
9eef97d108
commit
ae3cb0557d
|
@ -280,8 +280,10 @@ void *PX4Scheduler::_timer_thread(void *arg)
|
||||||
|
|
||||||
if (px4_ran_overtime && AP_HAL::millis() - last_ran_overtime > 2000) {
|
if (px4_ran_overtime && AP_HAL::millis() - last_ran_overtime > 2000) {
|
||||||
last_ran_overtime = AP_HAL::millis();
|
last_ran_overtime = AP_HAL::millis();
|
||||||
|
#if 0
|
||||||
printf("Overtime in task %d\n", (int)AP_Scheduler::current_task);
|
printf("Overtime in task %d\n", (int)AP_Scheduler::current_task);
|
||||||
hal.console->printf("Overtime in task %d\n", (int)AP_Scheduler::current_task);
|
hal.console->printf("Overtime in task %d\n", (int)AP_Scheduler::current_task);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return NULL;
|
return NULL;
|
||||||
|
|
Loading…
Reference in New Issue