mirror of https://github.com/ArduPilot/ardupilot
AP_CANManager: 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
75b3cec196
commit
14089d4919
|
@ -721,11 +721,11 @@ int16_t SLCAN::CANIface::receive(AP_HAL::CANFrame& out_frame, uint64_t& rx_time,
|
|||
uint32_t num_bytes = _port->available_locked(_serial_lock_key);
|
||||
// flush bytes from port
|
||||
while (num_bytes--) {
|
||||
int16_t ret = _port->read_locked(_serial_lock_key);
|
||||
if (ret < 0) {
|
||||
uint8_t b;
|
||||
if (!_port->read_locked(_serial_lock_key, b)) {
|
||||
break;
|
||||
}
|
||||
addByte(ret);
|
||||
addByte(b);
|
||||
if (!rx_queue_.space()) {
|
||||
break;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue