diff --git a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp index abea5965ad..5883c103f5 100644 --- a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp +++ b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp @@ -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; } diff --git a/libraries/AP_HAL_ChibiOS/hwdef/iomcu/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/iomcu/hwdef.dat index 914c907728..2c5c90bab3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/iomcu/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/iomcu/hwdef.dat @@ -121,3 +121,4 @@ define NO_FASTBOOT IOMCU_FW 1 MAIN_STACK 0x200 PROCESS_STACK 0x250 +define HAL_DISABLE_LOOP_DELAY