diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index a7b8da076ce422..1df2c56bca96d7 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -560,10 +560,6 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id) queued_waypoint_send(); break; - case MSG_STATUSTEXT: - // depreciated, use GCS_MAVLINK::send_statustext* - return false; - case MSG_FENCE_STATUS: #if GEOFENCE_ENABLED == ENABLED CHECK_PAYLOAD_SIZE(FENCE_STATUS);