From da889bdff5aa43ed086312f0d1fcb22bc5552e79 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 4 Aug 2017 18:10:38 +1000 Subject: [PATCH] Copter: move sending of meminfo up --- ArduCopter/GCS_Mavlink.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index ee326ed62b..eb4099b5ec 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -316,11 +316,6 @@ bool GCS_MAVLINK_Copter::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); copter.send_attitude(chan);