diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 901ca59e84..067423c729 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -182,10 +182,9 @@ public: static uint8_t streaming_channel_mask(void) { return chan_is_streaming; } /* - send a statustext message to active MAVLink connections, or a specific - one. This function is static so it can be called from any library. + send a statustext message to specific MAVLINK Connection + This function is static so it can be called from any library. */ - static void send_statustext_all(MAV_SEVERITY severity, const char *fmt, ...); static void send_statustext_chan(MAV_SEVERITY severity, uint8_t dest_chan, const char *fmt, ...); // send a PARAM_VALUE message to all active MAVLink connections. diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index fd9abed930..13a855b12e 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1141,20 +1141,6 @@ void GCS_MAVLINK::send_ahrs(AP_AHRS &ahrs) ahrs.get_error_yaw()); } -/* - send a statustext message to all active MAVLink connections - */ -void GCS_MAVLINK::send_statustext_all(MAV_SEVERITY severity, const char *fmt, ...) -{ - char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {}; - va_list arg_list; - va_start(arg_list, fmt); - hal.util->vsnprintf((char *)text, sizeof(text)-1, fmt, arg_list); - va_end(arg_list); - text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] = 0; - gcs().send_statustext(severity, mavlink_active | chan_is_streaming, text); -} - /* send a statustext message to specific MAVLink channel, zero indexed */