diff --git a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp index 921bde7712..c7d4568eab 100644 --- a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp +++ b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp @@ -198,7 +198,7 @@ static void main_loop() g_callbacks->loop(); /* - give up 250 microseconds of time if the INS loop hasn't + give up 50 microseconds of time if the INS loop hasn't called delay_microseconds_boost(), to ensure low priority drivers get a chance to run. Calling delay_microseconds_boost() means we have already given up @@ -207,7 +207,7 @@ static void main_loop() */ #ifndef HAL_DISABLE_LOOP_DELAY if (!schedulerInstance.check_called_boost()) { - hal.scheduler->delay_microseconds(250); + hal.scheduler->delay_microseconds(50); } #endif }