HAL_ChibiOS: disable loop() delay for iofirmware

This commit is contained in:
Andrew Tridgell 2018-10-30 09:20:33 +11:00
parent 1711b93602
commit 7e777d8b28
2 changed files with 3 additions and 0 deletions

View File

@ -208,9 +208,11 @@ static void main_loop()
time from the main loop, so we don't need to do it again
here
*/
#ifndef HAL_DISABLE_LOOP_DELAY
if (!schedulerInstance.check_called_boost()) {
hal.scheduler->delay_microseconds(250);
}
#endif
}
thread_running = false;
}

View File

@ -121,3 +121,4 @@ define NO_FASTBOOT
IOMCU_FW 1
MAIN_STACK 0x200
PROCESS_STACK 0x250
define HAL_DISABLE_LOOP_DELAY