diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index 4f13554643..5ea95fb3ce 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -101,14 +101,6 @@ void Tracker::send_location(mavlink_channel_t chan) ahrs.yaw_sensor); } -void Tracker::send_hwstatus(mavlink_channel_t chan) -{ - mavlink_msg_hwstatus_send( - chan, - 0, - 0); -} - void Tracker::send_nav_controller_output(mavlink_channel_t chan) { float alt_diff = (g.alt_source == ALT_SOURCE_BARO) ? nav_status.alt_difference_baro : nav_status.alt_difference_gps; @@ -220,11 +212,6 @@ bool GCS_MAVLINK_Tracker::try_send_message(enum ap_message id) tracker.send_simstate(chan); break; - case MSG_HWSTATUS: - CHECK_PAYLOAD_SIZE(HWSTATUS); - tracker.send_hwstatus(chan); - break; - default: return GCS_MAVLINK::try_send_message(id); } diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index 2f1b2f39f8..6d37ccf9ae 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -199,7 +199,6 @@ private: void send_heartbeat(mavlink_channel_t chan); void send_attitude(mavlink_channel_t chan); void send_location(mavlink_channel_t chan); - void send_hwstatus(mavlink_channel_t chan); void send_nav_controller_output(mavlink_channel_t chan); void send_simstate(mavlink_channel_t chan); void mavlink_check_target(const mavlink_message_t* msg);