HAL_Linux: don't prevent write while timer is busy

the timer can block on I2C writes, which causes the main loop to run
This commit is contained in:
Andrew Tridgell 2013-10-08 11:10:06 +11:00
parent 91511e6503
commit a216e1d239
1 changed files with 0 additions and 9 deletions

View File

@ -258,10 +258,6 @@ size_t LinuxUARTDriver::write(uint8_t c)
if (!_initialised) {
return 0;
}
if (hal.scheduler->in_timerprocess()) {
// not allowed from timers
return 0;
}
uint16_t _head;
while (BUF_SPACE(_writebuf) == 0) {
@ -283,11 +279,6 @@ size_t LinuxUARTDriver::write(const uint8_t *buffer, size_t size)
if (!_initialised) {
return 0;
}
if (hal.scheduler->in_timerprocess()) {
// not allowed from timers
return 0;
}
if (!_nonblocking_writes) {
/*
use the per-byte delay loop in write() above for blocking writes