diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 13517f4d1e..06c9e536df 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -344,11 +344,6 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) copter.send_vfr_hud(chan); break; - case MSG_RAW_IMU2: - CHECK_PAYLOAD_SIZE(SCALED_PRESSURE); - send_scaled_pressure(); - break; - case MSG_RPM: #if RPM_ENABLED == ENABLED CHECK_PAYLOAD_SIZE(RPM);