diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 0b2943f8b0..a46da47ebb 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -707,7 +707,6 @@ private: // GCS_Mavlink.cpp void gcs_send_heartbeat(void); - void send_rpm(mavlink_channel_t chan); // heli.cpp void heli_init(); diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 1d92d33329..d5ce0abd19 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -142,21 +142,6 @@ int16_t GCS_MAVLINK_Copter::vfr_hud_throttle() const return (int16_t)(copter.motors->get_throttle() * 100); } -/* - send RPM packet - */ -void NOINLINE Copter::send_rpm(mavlink_channel_t chan) -{ -#if RPM_ENABLED == ENABLED - 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 -} - /* send PID tuning message */ @@ -247,13 +232,6 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) switch(id) { - case MSG_RPM: -#if RPM_ENABLED == ENABLED - CHECK_PAYLOAD_SIZE(RPM); - copter.send_rpm(chan); -#endif - break; - case MSG_TERRAIN: #if AP_TERRAIN_AVAILABLE && AC_TERRAIN CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST);