diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 5db6326b2f..a21a5b1948 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -455,11 +455,6 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id) } break; - case MSG_EXTENDED_STATUS2: - CHECK_PAYLOAD_SIZE(MEMINFO); - send_meminfo(); - break; - case MSG_ATTITUDE: CHECK_PAYLOAD_SIZE(ATTITUDE); sub.send_attitude(chan);