Rover: improved loop() latency
This commit is contained in:
parent
1e7af3e101
commit
42255ebbc6
@ -623,10 +623,8 @@ void loop()
|
|||||||
fast_loopTimeStamp = millis();
|
fast_loopTimeStamp = millis();
|
||||||
|
|
||||||
scheduler.run(19000U);
|
scheduler.run(19000U);
|
||||||
}
|
} else {
|
||||||
if ((timer - fast_loopTimer) <= 19) {
|
hal.scheduler->delay_microseconds(500);
|
||||||
// we have plenty of time - be friendly to multi-tasking OSes
|
|
||||||
hal.scheduler->delay(1);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user