From cfa38df5286107cf949dc324c788bab43c51e598 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 28 Oct 2013 10:34:09 +1100 Subject: [PATCH] Plane: allow parameters to download at full speed --- ArduPlane/GCS_Mavlink.pde | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index e79ae368f8..c6e814644f 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -947,7 +947,8 @@ bool GCS_MAVLINK::stream_trigger(enum streams stream_num) // send at a much lower rate while handling waypoints and // parameter sends - if (waypoint_receiving || _queued_parameter != NULL) { + if ((stream_num != STREAM_PARAMS) && + (waypoint_receiving || _queued_parameter != NULL)) { rate *= 0.25; }