mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-20 15:48:29 -04:00
AP_HAL_ChibiOS: add discard_input method on UARTDriver
This commit is contained in:
parent
a8d03990ec
commit
8f54de4184
@ -564,6 +564,24 @@ uint32_t UARTDriver::txspace()
|
|||||||
return _writebuf.space();
|
return _writebuf.space();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool UARTDriver::discard_input()
|
||||||
|
{
|
||||||
|
if (lock_read_key != 0 || _uart_owner_thd != chThdGetSelfX()){
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
if (!_initialised) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
_readbuf.empty();
|
||||||
|
|
||||||
|
if (!_rts_is_active) {
|
||||||
|
update_rts_line();
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
int16_t UARTDriver::read()
|
int16_t UARTDriver::read()
|
||||||
{
|
{
|
||||||
if (lock_read_key != 0 || _uart_owner_thd != chThdGetSelfX()){
|
if (lock_read_key != 0 || _uart_owner_thd != chThdGetSelfX()){
|
||||||
|
@ -47,6 +47,8 @@ public:
|
|||||||
int16_t read_locked(uint32_t key) override;
|
int16_t read_locked(uint32_t key) override;
|
||||||
void _timer_tick(void) override;
|
void _timer_tick(void) override;
|
||||||
|
|
||||||
|
bool discard_input() override;
|
||||||
|
|
||||||
size_t write(uint8_t c) override;
|
size_t write(uint8_t c) override;
|
||||||
size_t write(const uint8_t *buffer, size_t size) override;
|
size_t write(const uint8_t *buffer, size_t size) override;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user