|
|
|
@ -12,13 +12,14 @@ AVRConsoleDriver::AVRConsoleDriver() :
@@ -12,13 +12,14 @@ AVRConsoleDriver::AVRConsoleDriver() :
|
|
|
|
|
{} |
|
|
|
|
|
|
|
|
|
// ConsoleDriver method implementations ///////////////////////////////////////
|
|
|
|
|
//
|
|
|
|
|
void AVRConsoleDriver::init(void* base_uart) { |
|
|
|
|
_base_uart = (AP_HAL::UARTDriver*) base_uart; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
void AVRConsoleDriver::backend_open() { |
|
|
|
|
_txbuf.allocate(128); |
|
|
|
|
_rxbuf.allocate(16); |
|
|
|
|
_user_backend = true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -27,22 +28,29 @@ void AVRConsoleDriver::backend_close() {
@@ -27,22 +28,29 @@ void AVRConsoleDriver::backend_close() {
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
int AVRConsoleDriver::backend_read(uint8_t *data, int len) { |
|
|
|
|
return 0; |
|
|
|
|
for (int i = 0; i < len; i++) { |
|
|
|
|
int b = _txbuf.pop(); |
|
|
|
|
if (b != -1) { |
|
|
|
|
data[i] = (uint8_t) b; |
|
|
|
|
} else { |
|
|
|
|
return i; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
return len; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
int AVRConsoleDriver::backend_write(const uint8_t *data, int len) { |
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
|
// Print method implementations /////////////////////////////////////////
|
|
|
|
|
|
|
|
|
|
size_t AVRConsoleDriver::write(uint8_t c) { |
|
|
|
|
if (_user_backend) { |
|
|
|
|
return 1; |
|
|
|
|
} else { |
|
|
|
|
return _base_uart->write(c); |
|
|
|
|
for (int i = 0; i < len; i++) { |
|
|
|
|
bool valid = _rxbuf.push(data[i]); |
|
|
|
|
if (!valid) { |
|
|
|
|
return i; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
return len; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// AVRConsoleDriver private method implementations ////////////////////////////
|
|
|
|
|
|
|
|
|
|
// BetterStream method implementations /////////////////////////////////////////
|
|
|
|
|
void AVRConsoleDriver::print_P(const prog_char_t *s) { |
|
|
|
|
char c; |
|
|
|
@ -72,6 +80,7 @@ void AVRConsoleDriver::_printf_P(const prog_char *fmt, ...) {
@@ -72,6 +80,7 @@ void AVRConsoleDriver::_printf_P(const prog_char *fmt, ...) {
|
|
|
|
|
// Stream method implementations /////////////////////////////////////////
|
|
|
|
|
int AVRConsoleDriver::available(void) { |
|
|
|
|
if (_user_backend) { |
|
|
|
|
// XXX TODO
|
|
|
|
|
return INT_MAX; |
|
|
|
|
} else { |
|
|
|
|
return _base_uart->available(); |
|
|
|
@ -80,6 +89,7 @@ int AVRConsoleDriver::available(void) {
@@ -80,6 +89,7 @@ int AVRConsoleDriver::available(void) {
|
|
|
|
|
|
|
|
|
|
int AVRConsoleDriver::txspace(void) { |
|
|
|
|
if (_user_backend) { |
|
|
|
|
// XXX TODO
|
|
|
|
|
return INT_MAX; |
|
|
|
|
} else { |
|
|
|
|
return _base_uart->txspace(); |
|
|
|
@ -88,7 +98,7 @@ int AVRConsoleDriver::txspace(void) {
@@ -88,7 +98,7 @@ int AVRConsoleDriver::txspace(void) {
|
|
|
|
|
|
|
|
|
|
int AVRConsoleDriver::read() { |
|
|
|
|
if (_user_backend) { |
|
|
|
|
return -1; |
|
|
|
|
return _rxbuf.pop();
|
|
|
|
|
} else { |
|
|
|
|
return _base_uart->read(); |
|
|
|
|
} |
|
|
|
@ -96,9 +106,66 @@ int AVRConsoleDriver::read() {
@@ -96,9 +106,66 @@ int AVRConsoleDriver::read() {
|
|
|
|
|
|
|
|
|
|
int AVRConsoleDriver::peek() { |
|
|
|
|
if (_user_backend) { |
|
|
|
|
// XXX TODO
|
|
|
|
|
return -1; |
|
|
|
|
} else { |
|
|
|
|
return _base_uart->peek(); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// Print method implementations /////////////////////////////////////////
|
|
|
|
|
|
|
|
|
|
size_t AVRConsoleDriver::write(uint8_t c) { |
|
|
|
|
if (_user_backend) { |
|
|
|
|
return (_txbuf.push(c) ? 1 : 0); |
|
|
|
|
} else { |
|
|
|
|
return _base_uart->write(c); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* AVRConsoleDriver::Buffer implementation. |
|
|
|
|
* A synchronous nonblocking ring buffer, based on the AVRUARTDriver::Buffer |
|
|
|
|
*/ |
|
|
|
|
|
|
|
|
|
bool AVRConsoleDriver::Buffer::allocate(int size) { |
|
|
|
|
_head = 0; |
|
|
|
|
_tail = 0; |
|
|
|
|
uint8_t shift; |
|
|
|
|
/* Hardcoded max size of 1024. sue me. */ |
|
|
|
|
for ( shift = 1; |
|
|
|
|
( 1 << shift ) < 1024 && ( 1 << shift) < size; |
|
|
|
|
shift++ |
|
|
|
|
) ; |
|
|
|
|
uint16_t tmpmask = (1 << shift) - 1; |
|
|
|
|
|
|
|
|
|
if ( _bytes != NULL ) { |
|
|
|
|
if ( _mask == tmpmask ) { |
|
|
|
|
return true; |
|
|
|
|
} |
|
|
|
|
free(_bytes); |
|
|
|
|
} |
|
|
|
|
_mask = tmpmask; |
|
|
|
|
_bytes = (uint8_t*) malloc(_mask+1); |
|
|
|
|
return (_bytes != NULL); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
bool AVRConsoleDriver::Buffer::push(uint8_t b) { |
|
|
|
|
uint16_t next = (_head + 1) & _mask; |
|
|
|
|
if ( next == _tail ) { |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
_bytes[_head] = b; |
|
|
|
|
_head = next; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
int AVRConsoleDriver::Buffer::pop() { |
|
|
|
|
if ( _tail == _head ) { |
|
|
|
|
return -1; |
|
|
|
|
} |
|
|
|
|
uint8_t b = _bytes[_tail]; |
|
|
|
|
_tail = ( _tail + 1 ) & _mask; |
|
|
|
|
return (int) b; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|