From b1c789f73de0afd1e7467953c4aa2df280a71e53 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 2 Mar 2019 09:38:47 +1100 Subject: [PATCH] Sub: move sending of RPM message up --- ArduSub/GCS_Mavlink.cpp | 22 ---------------------- ArduSub/Sub.h | 1 - 2 files changed, 23 deletions(-) diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index c0335e3ab1..238894a4dc 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -101,21 +101,6 @@ int16_t GCS_MAVLINK_Sub::vfr_hud_throttle() const return (int16_t)(sub.motors.get_throttle() * 100); } -/* - send RPM packet - */ -#if RPM_ENABLED == ENABLED -void NOINLINE Sub::send_rpm(mavlink_channel_t chan) -{ - if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) { - mavlink_msg_rpm_send( - chan, - rpm_sensor.get_rpm(0), - rpm_sensor.get_rpm(1)); - } -} -#endif - // Work around to get temperature sensor data out void GCS_MAVLINK_Sub::send_scaled_pressure3() { @@ -253,13 +238,6 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id) send_info(); break; - case MSG_RPM: -#if RPM_ENABLED == ENABLED - CHECK_PAYLOAD_SIZE(RPM); - sub.send_rpm(chan); -#endif - break; - case MSG_TERRAIN: #if AP_TERRAIN_AVAILABLE && AC_TERRAIN CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST); diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index ece5433c7f..050193a6ba 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -480,7 +480,6 @@ private: void gcs_send_heartbeat(void); void send_heartbeat(mavlink_channel_t chan); #if RPM_ENABLED == ENABLED - void send_rpm(mavlink_channel_t chan); void rpm_update(); #endif void Log_Write_Control_Tuning();