Copter: limit number of bytes read per GCS check

This commit is contained in:
Andrew Tridgell 2013-01-23 09:34:54 +11:00
parent f72b532405
commit 47cc247046
1 changed files with 2 additions and 2 deletions

View File

@ -877,8 +877,8 @@ GCS_MAVLINK::update(void)
status.packet_rx_drop_count = 0;
// 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);
#if CLI_ENABLED == ENABLED