mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL_ChibiOS: add and use a "bool read(c)" method to AP_HAL
this is much less likely to not work vs the int16_t equivalent
This commit is contained in:
parent
74207ea687
commit
130f2c3bc8
@ -736,31 +736,32 @@ ssize_t UARTDriver::read(uint8_t *buffer, uint16_t count)
|
||||
return ret;
|
||||
}
|
||||
|
||||
int16_t UARTDriver::read()
|
||||
bool UARTDriver::read(uint8_t &b)
|
||||
{
|
||||
if (_uart_owner_thd != chThdGetSelfX()) {
|
||||
return -1;
|
||||
return false;
|
||||
}
|
||||
|
||||
return UARTDriver::read_locked(0);
|
||||
return UARTDriver::read_locked(0, b);
|
||||
}
|
||||
|
||||
int16_t UARTDriver::read_locked(uint32_t key)
|
||||
bool UARTDriver::read_locked(uint32_t key, uint8_t &b)
|
||||
{
|
||||
if (lock_read_key != 0 && key != lock_read_key) {
|
||||
return -1;
|
||||
return false;
|
||||
}
|
||||
if (!_rx_initialised) {
|
||||
return -1;
|
||||
return false;
|
||||
}
|
||||
uint8_t byte;
|
||||
if (!_readbuf.read_byte(&byte)) {
|
||||
return -1;
|
||||
return false;
|
||||
}
|
||||
if (!_rts_is_active) {
|
||||
update_rts_line();
|
||||
}
|
||||
return byte;
|
||||
b = byte;
|
||||
return true;
|
||||
}
|
||||
|
||||
/* write one byte to the port */
|
||||
|
@ -52,9 +52,9 @@ public:
|
||||
uint32_t available_locked(uint32_t key) override;
|
||||
|
||||
uint32_t txspace() override;
|
||||
int16_t read() override;
|
||||
bool read(uint8_t &data) override WARN_IF_UNUSED;
|
||||
ssize_t read(uint8_t *buffer, uint16_t count) override;
|
||||
int16_t read_locked(uint32_t key) override;
|
||||
bool read_locked(uint32_t key, uint8_t &b) override WARN_IF_UNUSED;
|
||||
void _rx_timer_tick(void);
|
||||
void _tx_timer_tick(void);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user