mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_HAL_ChibiOS: override read(buffer,count) method to be more efficient
This commit is contained in:
parent
d259c03079
commit
6d9e563ede
@ -582,6 +582,27 @@ bool UARTDriver::discard_input()
|
||||
return true;
|
||||
}
|
||||
|
||||
ssize_t UARTDriver::read(uint8_t *buffer, uint16_t count)
|
||||
{
|
||||
if (lock_read_key != 0 || _uart_owner_thd != chThdGetSelfX()){
|
||||
return -1;
|
||||
}
|
||||
if (!_initialised) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
const uint32_t ret = _readbuf.read(buffer, count);
|
||||
if (ret == 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!_rts_is_active) {
|
||||
update_rts_line();
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int16_t UARTDriver::read()
|
||||
{
|
||||
if (lock_read_key != 0 || _uart_owner_thd != chThdGetSelfX()){
|
||||
|
@ -44,6 +44,7 @@ public:
|
||||
uint32_t available() override;
|
||||
uint32_t txspace() override;
|
||||
int16_t read() override;
|
||||
ssize_t read(uint8_t *buffer, uint16_t count) override;
|
||||
int16_t read_locked(uint32_t key) override;
|
||||
void _timer_tick(void) override;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user