From 7ca146878d47fa4e69cf5bf4c2f31e28dc5dd121 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 4 Aug 2017 18:22:51 +1000 Subject: [PATCH] Copter: move sending of camera_feedback up --- ArduCopter/GCS_Mavlink.cpp | 7 ------- 1 file changed, 7 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index eb4099b5ec..8dd66b6885 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -398,13 +398,6 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) #endif break; - case MSG_CAMERA_FEEDBACK: -#if CAMERA == ENABLED - CHECK_PAYLOAD_SIZE(CAMERA_FEEDBACK); - copter.camera.send_feedback(chan); -#endif - break; - case MSG_FENCE_STATUS: #if AC_FENCE == ENABLED CHECK_PAYLOAD_SIZE(FENCE_STATUS);