From a37c8eae1f4761472b2046dde7715e5c5ed4f531 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 3 May 2018 11:31:54 +1000 Subject: [PATCH] Rover: move try_send_message of RAW_IMU up to GCS_MAVLINK --- APMrover2/GCS_Mavlink.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index d557d9842c..0067a788e4 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -344,11 +344,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id) rover.send_vfr_hud(chan); break; - case MSG_RAW_IMU1: - CHECK_PAYLOAD_SIZE(RAW_IMU); - send_raw_imu(rover.ins, rover.compass); - break; - case MSG_RAW_IMU2: CHECK_PAYLOAD_SIZE(SCALED_PRESSURE); send_scaled_pressure();