diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 02179d975c..f471399788 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -267,30 +267,6 @@ void NOINLINE Sub::send_simstate(mavlink_channel_t chan) #endif } -void NOINLINE Sub::send_radio_out(mavlink_channel_t chan) -{ - mavlink_msg_servo_output_raw_send( - chan, - micros(), - 0, // port - hal.rcout->read(0), - hal.rcout->read(1), - hal.rcout->read(2), - hal.rcout->read(3), - hal.rcout->read(4), - hal.rcout->read(5), - hal.rcout->read(6), - hal.rcout->read(7), - hal.rcout->read(8), - hal.rcout->read(9), - hal.rcout->read(10), - hal.rcout->read(11), - hal.rcout->read(12), - hal.rcout->read(13), - hal.rcout->read(14), - hal.rcout->read(15)); -} - void NOINLINE Sub::send_vfr_hud(mavlink_channel_t chan) { mavlink_msg_vfr_hud_send( @@ -467,11 +443,6 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id) sub.send_nav_controller_output(chan); break; - case MSG_SERVO_OUTPUT_RAW: - CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW); - sub.send_radio_out(chan); - break; - case MSG_VFR_HUD: CHECK_PAYLOAD_SIZE(VFR_HUD); sub.send_vfr_hud(chan); diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 275dad5f08..f8bdbe957e 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -478,7 +478,6 @@ private: void send_extended_status1(mavlink_channel_t chan); void send_nav_controller_output(mavlink_channel_t chan); void send_simstate(mavlink_channel_t chan); - void send_radio_out(mavlink_channel_t chan); void send_vfr_hud(mavlink_channel_t chan); #if RPM_ENABLED == ENABLED void send_rpm(mavlink_channel_t chan);