HAL_Linux: run threads a bit more slowly

this was just wasting cycles
This commit is contained in:
Andrew Tridgell 2013-10-08 21:11:59 +11:00
parent 8f79a03c25
commit 0d682e74c1
1 changed files with 3 additions and 3 deletions

View File

@ -214,7 +214,7 @@ void *LinuxScheduler::_timer_thread(void)
{
_setup_realtime(32768);
while (true) {
_microsleep(1000);
_microsleep(5000);
// run registered timers
_run_timers(true);
@ -246,7 +246,7 @@ void *LinuxScheduler::_uart_thread(void)
{
_setup_realtime(32768);
while (true) {
_microsleep(1000);
_microsleep(10000);
// process any pending serial bytes
((LinuxUARTDriver *)hal.uartA)->_timer_tick();
@ -260,7 +260,7 @@ void *LinuxScheduler::_io_thread(void)
{
_setup_realtime(32768);
while (true) {
_microsleep(1000);
_microsleep(20000);
// process any pending storage writes
((LinuxStorage *)hal.storage)->_timer_tick();