From 47cc247046418b20228bfe2a3fd7770f8d4b6f86 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 23 Jan 2013 09:34:54 +1100 Subject: [PATCH] Copter: limit number of bytes read per GCS check --- ArduCopter/GCS_Mavlink.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 553163ecdb..fdde74009c 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -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