mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Copter: limit number of bytes read per GCS check
This commit is contained in:
parent
f72b532405
commit
47cc247046
@ -877,8 +877,8 @@ GCS_MAVLINK::update(void)
|
|||||||
status.packet_rx_drop_count = 0;
|
status.packet_rx_drop_count = 0;
|
||||||
|
|
||||||
// process received bytes
|
// process received bytes
|
||||||
while(comm_get_available(chan))
|
uint16_t nbytes = comm_get_available(chan);
|
||||||
{
|
for (uint16_t i=0; i<nbytes; i++) {
|
||||||
uint8_t c = comm_receive_ch(chan);
|
uint8_t c = comm_receive_ch(chan);
|
||||||
|
|
||||||
#if CLI_ENABLED == ENABLED
|
#if CLI_ENABLED == ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user