diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 00b24df989..a9d3792873 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -293,14 +293,6 @@ void NOINLINE Sub::send_simstate(mavlink_channel_t chan) #endif } -void NOINLINE Sub::send_hwstatus(mavlink_channel_t chan) -{ - mavlink_msg_hwstatus_send( - chan, - hal.analogin->board_voltage()*1000, - 0); -} - void NOINLINE Sub::send_radio_out(mavlink_channel_t chan) { mavlink_msg_servo_output_raw_send( @@ -585,11 +577,6 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id) send_ahrs2(sub.ahrs); break; - case MSG_HWSTATUS: - CHECK_PAYLOAD_SIZE(HWSTATUS); - sub.send_hwstatus(chan); - break; - case MSG_MOUNT_STATUS: #if MOUNT == ENABLED CHECK_PAYLOAD_SIZE(MOUNT_STATUS); diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 2cf46f0d80..53a61f442d 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -483,7 +483,6 @@ private: void send_location(mavlink_channel_t chan); void send_nav_controller_output(mavlink_channel_t chan); void send_simstate(mavlink_channel_t chan); - void send_hwstatus(mavlink_channel_t chan); void send_radio_out(mavlink_channel_t chan); void send_vfr_hud(mavlink_channel_t chan); #if RPM_ENABLED == ENABLED