diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index cbbaf82f45..663bc260ab 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -299,11 +299,6 @@ bool GCS_MAVLINK_Rover::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: // send extended status only once vehicle has been initialised