diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 478baf5fd5..40ed62cf62 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -414,11 +414,6 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id) } switch (id) { - case MSG_HEARTBEAT: - CHECK_PAYLOAD_SIZE(HEARTBEAT); - last_heartbeat_time = AP_HAL::millis(); - send_heartbeat(); - return true; case MSG_EXTENDED_STATUS1: CHECK_PAYLOAD_SIZE(SYS_STATUS);