Browse Source

AP_HAL_SITL: add discard_input method on UARTDriver

c415-sdk
Peter Barker 5 years ago committed by Andrew Tridgell
parent
commit
80615c44ff
  1. 6
      libraries/AP_HAL_SITL/UARTDriver.cpp
  2. 2
      libraries/AP_HAL_SITL/UARTDriver.h

6
libraries/AP_HAL_SITL/UARTDriver.cpp

@ -174,6 +174,12 @@ int16_t UARTDriver::read(void) @@ -174,6 +174,12 @@ int16_t UARTDriver::read(void)
return c;
}
bool UARTDriver::discard_input(void)
{
_readbuffer.empty();
return true;
}
void UARTDriver::flush(void)
{
}

2
libraries/AP_HAL_SITL/UARTDriver.h

@ -49,6 +49,8 @@ public: @@ -49,6 +49,8 @@ public:
uint32_t txspace() override;
int16_t read() 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;

Loading…
Cancel
Save