mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: reduced delay time in main loop to 50us
this allows for faster loop rates, and seems to be enough in testing
This commit is contained in:
parent
958b1032c5
commit
bd47aba5ca
|
@ -198,7 +198,7 @@ static void main_loop()
|
||||||
g_callbacks->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
|
called delay_microseconds_boost(), to ensure low priority
|
||||||
drivers get a chance to run. Calling
|
drivers get a chance to run. Calling
|
||||||
delay_microseconds_boost() means we have already given up
|
delay_microseconds_boost() means we have already given up
|
||||||
|
@ -207,7 +207,7 @@ static void main_loop()
|
||||||
*/
|
*/
|
||||||
#ifndef HAL_DISABLE_LOOP_DELAY
|
#ifndef HAL_DISABLE_LOOP_DELAY
|
||||||
if (!schedulerInstance.check_called_boost()) {
|
if (!schedulerInstance.check_called_boost()) {
|
||||||
hal.scheduler->delay_microseconds(250);
|
hal.scheduler->delay_microseconds(50);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue