HAL_PX4: fixed blocking IO in UART driver

This commit is contained in:
Andrew Tridgell 2013-01-22 21:52:21 +11:00
parent 6ffa18fa61
commit 89cb3fbd61
2 changed files with 17 additions and 9 deletions

View File

@ -38,6 +38,12 @@ void PX4UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
_devpath, strerror(errno)); _devpath, strerror(errno));
return; return;
} }
// always set it non-blocking for the low level IO
unsigned v;
v = fcntl(_fd, F_GETFL, 0);
fcntl(_fd, F_SETFL, v | O_NONBLOCK);
_initialised = true; _initialised = true;
if (rxS == 0) { if (rxS == 0) {
rxS = 128; rxS = 128;
@ -101,14 +107,7 @@ void PX4UARTDriver::flush() {}
bool PX4UARTDriver::is_initialized() { return true; } bool PX4UARTDriver::is_initialized() { return true; }
void PX4UARTDriver::set_blocking_writes(bool blocking) void PX4UARTDriver::set_blocking_writes(bool blocking)
{ {
unsigned v; _nonblocking_writes = !blocking;
v = fcntl(_fd, F_GETFL, 0);
if (blocking) {
v &= ~O_NONBLOCK;
} else {
v |= O_NONBLOCK;
}
fcntl(_fd, F_SETFL, v);
} }
bool PX4UARTDriver::tx_pending() { return false; } bool PX4UARTDriver::tx_pending() { return false; }
@ -218,9 +217,16 @@ int16_t PX4UARTDriver::read()
*/ */
size_t PX4UARTDriver::write(uint8_t c) size_t PX4UARTDriver::write(uint8_t c)
{ {
if (txspace() == 0) { if (!_initialised) {
return 0; return 0;
} }
uint16_t _head;
while (BUF_SPACE(_writebuf) == 0) {
if (_nonblocking_writes) {
return 0;
}
hal.scheduler->delay(1);
}
_writebuf[_writebuf_tail] = c; _writebuf[_writebuf_tail] = c;
BUF_ADVANCETAIL(_writebuf, 1); BUF_ADVANCETAIL(_writebuf, 1);
return 1; return 1;

View File

@ -48,6 +48,8 @@ private:
int _fd; int _fd;
void _vdprintf(int fd, const char *fmt, va_list ap); void _vdprintf(int fd, const char *fmt, va_list ap);
bool _nonblocking_writes;
// we use in-task ring buffers to reduce the system call cost // we use in-task ring buffers to reduce the system call cost
// of ::read() and ::write() in the main loop // of ::read() and ::write() in the main loop
uint8_t *_readbuf; uint8_t *_readbuf;