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