diff --git a/libraries/GCS_MAVLink/GCS_Param.cpp b/libraries/GCS_MAVLink/GCS_Param.cpp index 397737dc15..d6b1c4d6d1 100644 --- a/libraries/GCS_MAVLink/GCS_Param.cpp +++ b/libraries/GCS_MAVLink/GCS_Param.cpp @@ -37,6 +37,12 @@ GCS_MAVLINK::queued_param_send() // send parameter async replies uint8_t async_replies_sent_count = send_parameter_async_replies(); + // now send the streaming parameters (from PARAM_REQUEST_LIST) + if (_queued_parameter == nullptr) { + // .... or not.... + return; + } + const uint32_t tnow = AP_HAL::millis(); const uint32_t tstart = AP_HAL::micros(); @@ -64,10 +70,6 @@ GCS_MAVLINK::queued_param_send() } count -= async_replies_sent_count; - if (_queued_parameter == nullptr) { - return; - } - while (count && _queued_parameter != nullptr) { char param_name[AP_MAX_NAME_SIZE]; _queued_parameter->copy_name_token(_queued_parameter_token, param_name, sizeof(param_name), true);