@ -2103,6 +2103,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
switch(id) {
case MSG_NEXT_PARAM:
CHECK_PAYLOAD_SIZE(PARAM_VALUE);
queued_param_send();
ret = true;
break;
case MSG_HWSTATUS:
CHECK_PAYLOAD_SIZE(HWSTATUS);
send_hwstatus();