diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 3dcb183f17..3cb61e95b4 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -307,11 +307,6 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) #endif switch(id) { - case MSG_HEARTBEAT: - CHECK_PAYLOAD_SIZE(HEARTBEAT); - last_heartbeat_time = AP_HAL::millis(); - send_heartbeat(); - break; case MSG_EXTENDED_STATUS1: // send extended status only once vehicle has been initialised