mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: RDS02UF: avoid nuking partial messages after good parse
there may be a fragment of another packet in the buffer
This commit is contained in:
parent
61e83dcd0e
commit
7a930637e0
|
@ -97,8 +97,9 @@ bool AP_RangeFinder_RDS02UF::get_reading(float &distance_m)
|
|||
}
|
||||
}
|
||||
|
||||
// reset buffer
|
||||
body_length = 0;
|
||||
// consume this message:
|
||||
move_header_in_buffer(ARRAY_SIZE(u.parse_buffer));
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue