mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_CANManager: fixed usage of read_locked
this didn't actually cause an issue, but is wrong
This commit is contained in:
parent
9a29bf3f05
commit
a5fd60ec71
@ -722,7 +722,7 @@ int16_t SLCAN::CANIface::receive(AP_HAL::CANFrame& out_frame, uint64_t& rx_time,
|
|||||||
// flush bytes from port
|
// flush bytes from port
|
||||||
while (num_bytes--) {
|
while (num_bytes--) {
|
||||||
uint8_t b;
|
uint8_t b;
|
||||||
if (!_port->read_locked(&b, 1, _serial_lock_key)) {
|
if (_port->read_locked(&b, 1, _serial_lock_key) != 1) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
addByte(b);
|
addByte(b);
|
||||||
|
Loading…
Reference in New Issue
Block a user