AP_HAL_SITL: moved UART port locking up to AP_HAL

This commit is contained in:
Andrew Tridgell 2023-06-26 19:52:07 +10:00
parent ceb07c3f7b
commit 4f81a40066
2 changed files with 17 additions and 51 deletions

View File

@ -54,7 +54,7 @@ bool UARTDriver::_console;
/* UARTDriver method implementations */
void UARTDriver::begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
{
if (_portNumber >= ARRAY_SIZE(_sitlState->_uart_path)) {
AP_HAL::panic("port number out of range; you may need to extend _sitlState->_uart_path");
@ -195,11 +195,11 @@ void UARTDriver::begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
_set_nonblocking(_fd);
}
void UARTDriver::end()
void UARTDriver::_end()
{
}
uint32_t UARTDriver::available(void)
uint32_t UARTDriver::_available(void)
{
_check_connection();
@ -219,26 +219,18 @@ uint32_t UARTDriver::txspace(void)
return _writebuffer.space();
}
bool UARTDriver::read(uint8_t &c)
{
if (read(&c, 1) == 0) {
return false;
}
return true;
}
ssize_t UARTDriver::read(uint8_t *buffer, uint16_t count)
ssize_t UARTDriver::_read(uint8_t *buffer, uint16_t count)
{
return _readbuffer.read(buffer, count);
}
bool UARTDriver::discard_input(void)
bool UARTDriver::_discard_input(void)
{
_readbuffer.clear();
return true;
}
void UARTDriver::flush(void)
void UARTDriver::_flush(void)
{
// flush the write buffer - but don't fail and don't
// infinitely-loop. This is not a good definition of "flush", but
@ -262,20 +254,7 @@ void UARTDriver::flush(void)
}
}
// size_t UARTDriver::write(uint8_t c)
// {
// if (txspace() <= 0) {
// return 0;
// }
// _writebuffer.write(&c, 1);
// return 1;
// }
size_t UARTDriver::write(uint8_t c)
{
return write(&c, 1);
}
size_t UARTDriver::write(const uint8_t *buffer, size_t size)
size_t UARTDriver::_write(const uint8_t *buffer, size_t size)
{
if (txspace() <= size) {
size = txspace();

View File

@ -25,39 +25,18 @@ public:
_listen_fd = -1;
}
/* Implementations of UARTDriver virtual methods */
void begin(uint32_t b) override {
begin(b, 0, 0);
}
void begin(uint32_t b, uint16_t rxS, uint16_t txS) override;
void end() override;
void flush() override;
bool is_initialized() override {
return true;
}
ssize_t get_system_outqueue_length() const;
void set_blocking_writes(bool blocking) override
{
_nonblocking_writes = !blocking;
}
bool tx_pending() override {
return false;
}
/* Implementations of Stream virtual methods */
uint32_t available() override;
uint32_t txspace() override;
bool read(uint8_t &b) override WARN_IF_UNUSED;
ssize_t read(uint8_t *buffer, uint16_t count) override;
bool discard_input() override;
/* Implementations of Print virtual methods */
size_t write(uint8_t c) override;
size_t write(const uint8_t *buffer, size_t size) override;
bool _unbuffered_writes;
@ -83,7 +62,7 @@ public:
A return value of zero means the HAL does not support this API
*/
uint64_t receive_time_constraint_us(uint16_t nbytes) override;
private:
int _fd;
@ -98,7 +77,6 @@ private:
struct sockaddr_in _listen_sockaddr;
int _serial_port;
static bool _console;
bool _nonblocking_writes;
ByteBuffer _readbuffer{16384};
ByteBuffer _writebuffer{16384};
@ -147,6 +125,15 @@ private:
uint32_t first_emit_micros_us;
} logic_async_csv;
uint16_t read_from_async_csv(uint8_t *buffer, uint16_t space);
protected:
void _begin(uint32_t b, uint16_t rxS, uint16_t txS) override;
size_t _write(const uint8_t *buffer, size_t size) override;
ssize_t _read(uint8_t *buffer, uint16_t count) override;
uint32_t _available() override;
void _end() override;
void _flush() override;
bool _discard_input() override;
};
#endif