From 88883c7c7f4ac895ad0e1d73413ba2ebd57c8425 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 3 May 2018 11:38:41 +1000 Subject: [PATCH] Copter: move try_send_message sending of sensor offsets up --- ArduCopter/GCS_Mavlink.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index df522004d2..13517f4d1e 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -349,11 +349,6 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) send_scaled_pressure(); break; - case MSG_RAW_IMU3: - CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS); - send_sensor_offsets(copter.ins, copter.compass); - break; - case MSG_RPM: #if RPM_ENABLED == ENABLED CHECK_PAYLOAD_SIZE(RPM);