mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Common: removed set_blocking_writes
and moved to top level locking in UARTs
This commit is contained in:
parent
4087e0b215
commit
2d28b59661
@ -6,24 +6,23 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
class DummyUart: public AP_HAL::UARTDriver {
|
||||
public:
|
||||
void begin(uint32_t baud) override { };
|
||||
void begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) override { };
|
||||
void end() override { };
|
||||
void flush() override { };
|
||||
bool is_initialized() override { return true; };
|
||||
void set_blocking_writes(bool blocking) override { };
|
||||
bool tx_pending() override { return false; };
|
||||
uint32_t available() override { return 1; };
|
||||
uint32_t txspace() override { return _txspace; };
|
||||
bool read(uint8_t &c) override { return false; };
|
||||
|
||||
bool discard_input() override { return true; };
|
||||
size_t write(uint8_t c) override { return 1; };
|
||||
size_t write(const uint8_t *buffer, size_t size) override { return 1; };
|
||||
void set_txspace(uint32_t space) {
|
||||
_txspace = space;
|
||||
}
|
||||
uint32_t _txspace;
|
||||
|
||||
protected:
|
||||
uint32_t _available() override { return 1; };
|
||||
void _begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) override { };
|
||||
void _end() override { };
|
||||
void _flush() override { };
|
||||
size_t _write(const uint8_t *buffer, size_t size) override { return 1; };
|
||||
ssize_t _read(uint8_t *buf, uint16_t count) override { return 0; };
|
||||
bool _discard_input() override { return false; }
|
||||
};
|
||||
|
||||
static DummyUart test_uart;
|
||||
|
@ -45,24 +45,22 @@ void print_vprintf(AP_HAL::BetterStream *s, const char *fmt, va_list ap) {
|
||||
|
||||
class DummyUart: public AP_HAL::UARTDriver {
|
||||
public:
|
||||
void begin(uint32_t baud) override { };
|
||||
void begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) override { };
|
||||
void end() override { };
|
||||
void flush() override { };
|
||||
bool is_initialized() override { return true; };
|
||||
void set_blocking_writes(bool blocking) override { };
|
||||
bool tx_pending() override { return false; };
|
||||
uint32_t available() override { return 1; };
|
||||
uint32_t txspace() override { return _txspace; };
|
||||
bool read(uint8_t &c) override { return false; };
|
||||
|
||||
bool discard_input() override { return true; };
|
||||
size_t write(uint8_t c) override { return 1; };
|
||||
size_t write(const uint8_t *buffer, size_t size) override { return 1; };
|
||||
void set_txspace(uint32_t space) {
|
||||
_txspace = space;
|
||||
}
|
||||
uint32_t _txspace;
|
||||
protected:
|
||||
void _begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) override { };
|
||||
ssize_t _read(uint8_t *buf, uint16_t size) override { return 0; };
|
||||
void _end() override { };
|
||||
void _flush() override { };
|
||||
uint32_t _available() override { return 1; };
|
||||
size_t _write(const uint8_t *buffer, size_t size) override { return 1; };
|
||||
bool _discard_input() override { return false; }
|
||||
};
|
||||
|
||||
static DummyUart test_uart;
|
||||
|
Loading…
Reference in New Issue
Block a user