Browse Source

HAL_Linux: run threads a bit more slowly

this was just wasting cycles
mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
0d682e74c1
  1. 6
      libraries/AP_HAL_Linux/Scheduler.cpp

6
libraries/AP_HAL_Linux/Scheduler.cpp

@ -214,7 +214,7 @@ void *LinuxScheduler::_timer_thread(void) @@ -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) @@ -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) @@ -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();

Loading…
Cancel
Save