From eed73749f92c0eb8a98750e24b8f5c2317cce2f2 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 1 Mar 2019 10:32:26 +1100 Subject: [PATCH] Copter: move sending of send_pid_tuning up --- ArduCopter/GCS_Mavlink.cpp | 5 ----- ArduCopter/GCS_Mavlink.h | 2 +- 2 files changed, 1 insertion(+), 6 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index fdfdcdd684..de24cc0af9 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -268,11 +268,6 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) // unused break; - case MSG_PID_TUNING: - CHECK_PAYLOAD_SIZE(PID_TUNING); - send_pid_tuning(); - break; - case MSG_ADSB_VEHICLE: #if ADSB_ENABLED == ENABLED CHECK_PAYLOAD_SIZE(ADSB_VEHICLE); diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index 631d0b72ff..04dc9e1060 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/GCS_Mavlink.h @@ -64,6 +64,6 @@ private: int16_t vfr_hud_throttle() const override; float vfr_hud_alt() const override; - void send_pid_tuning(); + void send_pid_tuning() override; };