diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 70d34ea02d..1c5c59f130 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -329,11 +329,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id) } break; - case MSG_GPS_RAW: - CHECK_PAYLOAD_SIZE(GPS_RAW_INT); - send_gps_raw(rover.gps); - break; - case MSG_SERVO_OUT: CHECK_PAYLOAD_SIZE(RC_CHANNELS_SCALED); rover.send_servo_out(chan);