mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_HAL_AVR: Console uses only sized int types
This commit is contained in:
parent
8879cbbc69
commit
dfdc14f583
@ -27,9 +27,9 @@ void AVRConsoleDriver::backend_close() {
|
|||||||
_user_backend = false;
|
_user_backend = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
int AVRConsoleDriver::backend_read(uint8_t *data, int len) {
|
size_t AVRConsoleDriver::backend_read(uint8_t *data, size_t len) {
|
||||||
for (int i = 0; i < len; i++) {
|
for (size_t i = 0; i < len; i++) {
|
||||||
int b = _txbuf.pop();
|
int16_t b = _txbuf.pop();
|
||||||
if (b != -1) {
|
if (b != -1) {
|
||||||
data[i] = (uint8_t) b;
|
data[i] = (uint8_t) b;
|
||||||
} else {
|
} else {
|
||||||
@ -39,8 +39,8 @@ int AVRConsoleDriver::backend_read(uint8_t *data, int len) {
|
|||||||
return len;
|
return len;
|
||||||
}
|
}
|
||||||
|
|
||||||
int AVRConsoleDriver::backend_write(const uint8_t *data, int len) {
|
size_t AVRConsoleDriver::backend_write(const uint8_t *data, size_t len) {
|
||||||
for (int i = 0; i < len; i++) {
|
for (size_t i = 0; i < len; i++) {
|
||||||
bool valid = _rxbuf.push(data[i]);
|
bool valid = _rxbuf.push(data[i]);
|
||||||
if (!valid) {
|
if (!valid) {
|
||||||
return i;
|
return i;
|
||||||
@ -78,7 +78,7 @@ void AVRConsoleDriver::_printf_P(const prog_char *fmt, ...) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Stream method implementations /////////////////////////////////////////
|
// Stream method implementations /////////////////////////////////////////
|
||||||
int AVRConsoleDriver::available(void) {
|
int16_t AVRConsoleDriver::available(void) {
|
||||||
if (_user_backend) {
|
if (_user_backend) {
|
||||||
return _rxbuf.bytes_used();
|
return _rxbuf.bytes_used();
|
||||||
} else {
|
} else {
|
||||||
@ -86,7 +86,7 @@ int AVRConsoleDriver::available(void) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
int AVRConsoleDriver::txspace(void) {
|
int16_t AVRConsoleDriver::txspace(void) {
|
||||||
if (_user_backend) {
|
if (_user_backend) {
|
||||||
return _rxbuf.bytes_free();
|
return _rxbuf.bytes_free();
|
||||||
} else {
|
} else {
|
||||||
@ -94,7 +94,7 @@ int AVRConsoleDriver::txspace(void) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
int AVRConsoleDriver::read() {
|
int16_t AVRConsoleDriver::read() {
|
||||||
if (_user_backend) {
|
if (_user_backend) {
|
||||||
return _rxbuf.pop();
|
return _rxbuf.pop();
|
||||||
} else {
|
} else {
|
||||||
@ -102,7 +102,7 @@ int AVRConsoleDriver::read() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
int AVRConsoleDriver::peek() {
|
int16_t AVRConsoleDriver::peek() {
|
||||||
if (_user_backend) {
|
if (_user_backend) {
|
||||||
return _rxbuf.peek();
|
return _rxbuf.peek();
|
||||||
} else {
|
} else {
|
||||||
@ -126,7 +126,7 @@ size_t AVRConsoleDriver::write(uint8_t c) {
|
|||||||
* A synchronous nonblocking ring buffer, based on the AVRUARTDriver::Buffer
|
* A synchronous nonblocking ring buffer, based on the AVRUARTDriver::Buffer
|
||||||
*/
|
*/
|
||||||
|
|
||||||
bool AVRConsoleDriver::Buffer::allocate(int size) {
|
bool AVRConsoleDriver::Buffer::allocate(uint16_t size) {
|
||||||
_head = 0;
|
_head = 0;
|
||||||
_tail = 0;
|
_tail = 0;
|
||||||
uint8_t shift;
|
uint8_t shift;
|
||||||
@ -158,21 +158,21 @@ bool AVRConsoleDriver::Buffer::push(uint8_t b) {
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
int AVRConsoleDriver::Buffer::pop() {
|
int16_t AVRConsoleDriver::Buffer::pop() {
|
||||||
if ( _tail == _head ) {
|
if ( _tail == _head ) {
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
uint8_t b = _bytes[_tail];
|
uint8_t b = _bytes[_tail];
|
||||||
_tail = ( _tail + 1 ) & _mask;
|
_tail = ( _tail + 1 ) & _mask;
|
||||||
return (int) b;
|
return (int16_t) b;
|
||||||
}
|
}
|
||||||
|
|
||||||
int AVRConsoleDriver::Buffer::peek() {
|
int16_t AVRConsoleDriver::Buffer::peek() {
|
||||||
if ( _tail == _head ) {
|
if ( _tail == _head ) {
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
uint8_t b = _bytes[_tail];
|
uint8_t b = _bytes[_tail];
|
||||||
return (int) b;
|
return (int16_t) b;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t AVRConsoleDriver::Buffer::bytes_used() {
|
uint16_t AVRConsoleDriver::Buffer::bytes_used() {
|
||||||
|
@ -13,8 +13,8 @@ public:
|
|||||||
void init(void* baseuartdriver);
|
void init(void* baseuartdriver);
|
||||||
void backend_open();
|
void backend_open();
|
||||||
void backend_close();
|
void backend_close();
|
||||||
int backend_read(uint8_t *data, int len);
|
size_t backend_read(uint8_t *data, size_t len);
|
||||||
int backend_write(const uint8_t *data, int len);
|
size_t backend_write(const uint8_t *data, size_t len);
|
||||||
|
|
||||||
/* Implementations of BetterStream virtual methods */
|
/* Implementations of BetterStream virtual methods */
|
||||||
void print_P(const prog_char_t *s);
|
void print_P(const prog_char_t *s);
|
||||||
@ -25,20 +25,20 @@ public:
|
|||||||
__attribute__ ((format(__printf__, 2, 3)));
|
__attribute__ ((format(__printf__, 2, 3)));
|
||||||
|
|
||||||
/* Implementations of Stream virtual methods */
|
/* Implementations of Stream virtual methods */
|
||||||
int available();
|
int16_t available();
|
||||||
int txspace();
|
int16_t txspace();
|
||||||
int read();
|
int16_t read();
|
||||||
int peek();
|
int16_t peek();
|
||||||
|
|
||||||
/* Implementations of Print virtual methods */
|
/* Implementations of Print virtual methods */
|
||||||
size_t write(uint8_t c);
|
size_t write(uint8_t c);
|
||||||
private:
|
private:
|
||||||
struct Buffer {
|
struct Buffer {
|
||||||
/* public methods:*/
|
/* public methods:*/
|
||||||
bool allocate(int size);
|
bool allocate(uint16_t size);
|
||||||
bool push(uint8_t b);
|
bool push(uint8_t b);
|
||||||
int pop();
|
int16_t pop();
|
||||||
int peek();
|
int16_t peek();
|
||||||
|
|
||||||
uint16_t bytes_free();
|
uint16_t bytes_free();
|
||||||
uint16_t bytes_used();
|
uint16_t bytes_used();
|
||||||
|
Loading…
Reference in New Issue
Block a user