mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_IOMCU: read many bytes using read(buffer, len) method
This commit is contained in:
parent
e0728aa088
commit
a6831805f1
@ -516,11 +516,7 @@ bool AP_IOMCU::read_registers(uint8_t page, uint8_t offset, uint8_t count, uint1
|
|||||||
protocol_fail_count++;
|
protocol_fail_count++;
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
for (uint8_t i=0; i<n; i++) {
|
uart.read(b, MIN(n, sizeof(pkt)));
|
||||||
if (i < sizeof(pkt)) {
|
|
||||||
b[i] = uart.read();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t got_crc = pkt.crc;
|
uint8_t got_crc = pkt.crc;
|
||||||
pkt.crc = 0;
|
pkt.crc = 0;
|
||||||
|
Loading…
Reference in New Issue
Block a user