mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Mount_Alexmos: critical fix to avoid endless loop if byte arrive to fast in serial buffer
This fix reads the number of bytes available and iterates on it instead of looking for new bytes in the serial buffer (potentially forever)
This commit is contained in:
parent
46e92f99fe
commit
24af65a41a
@ -214,7 +214,10 @@ void AP_Mount_Alexmos::parse_body()
|
||||
void AP_Mount_Alexmos::read_incoming()
|
||||
{
|
||||
uint8_t data;
|
||||
while (_port->available()) {
|
||||
int16_t numc;
|
||||
|
||||
numc = _port->available();
|
||||
for (int16_t i = 0; i < numc; i++) { // Process bytes received
|
||||
data = _port->read();
|
||||
switch (_step) {
|
||||
case 0:
|
||||
|
Loading…
Reference in New Issue
Block a user