From 005797c327c0a46f588932ded51dedee5eefb9c9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 29 Apr 2017 14:36:42 +1000 Subject: [PATCH] AntennaTracker: use common send_queued_parameters() --- AntennaTracker/GCS_Mavlink.cpp | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index e83ca6a241..6e06722f52 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -368,14 +368,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { void GCS_MAVLINK_Tracker::data_stream_send(void) { - 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); - } - } + send_queued_parameters(); if (tracker.in_mavlink_delay) { // don't send any other stream types while in the delay callback