From 22791b72725f56ccbf6aa5c5e745b032d41a1622 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 29 Apr 2017 14:36:42 +1000 Subject: [PATCH] Copter: use common send_queued_parameters() --- ArduCopter/GCS_Mavlink.cpp | 11 +---------- 1 file changed, 1 insertion(+), 10 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index e7a2037029..a4de843ff0 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -712,16 +712,7 @@ GCS_MAVLINK_Copter::data_stream_send(void) copter.gcs_out_of_time = false; - if (_queued_parameter != nullptr) { - if (streamRates[STREAM_PARAMS].get() <= 0) { - streamRates[STREAM_PARAMS].set(10); - } - if (stream_trigger(STREAM_PARAMS)) { - send_message(MSG_NEXT_PARAM); - } - // don't send anything else at the same time as parameters - return; - } + send_queued_parameters(); if (copter.gcs_out_of_time) return;