diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp
index 4f81e86cd1..4dbedf8d84 100644
--- a/ArduSub/GCS_Mavlink.cpp
+++ b/ArduSub/GCS_Mavlink.cpp
@@ -89,20 +89,6 @@ MAV_STATE GCS_MAVLINK_Sub::system_status() const
     return MAV_STATE_STANDBY;
 }
 
-NOINLINE void Sub::send_attitude(mavlink_channel_t chan)
-{
-    const Vector3f &gyro = ins.get_gyro();
-    mavlink_msg_attitude_send(
-        chan,
-        millis(),
-        ahrs.roll,
-        ahrs.pitch,
-        ahrs.yaw,
-        gyro.x,
-        gyro.y,
-        gyro.z);
-}
-
 #if AC_FENCE == ENABLED
 NOINLINE void Sub::send_limits_status(mavlink_channel_t chan)
 {
@@ -494,11 +480,6 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
         }
         break;
 
-    case MSG_ATTITUDE:
-        CHECK_PAYLOAD_SIZE(ATTITUDE);
-        sub.send_attitude(chan);
-        break;
-
     case MSG_LOCATION:
         CHECK_PAYLOAD_SIZE(GLOBAL_POSITION_INT);
         sub.send_location(chan);
diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h
index 522c7a1a0b..63e86f8399 100644
--- a/ArduSub/Sub.h
+++ b/ArduSub/Sub.h
@@ -474,7 +474,6 @@ private:
     void gcs_send_heartbeat(void);
     void gcs_send_deferred(void);
     void send_heartbeat(mavlink_channel_t chan);
-    void send_attitude(mavlink_channel_t chan);
     void send_limits_status(mavlink_channel_t chan);
     void send_extended_status1(mavlink_channel_t chan);
     void send_location(mavlink_channel_t chan);