diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index 919a7c7305..6e6d83bc2c 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -464,7 +464,7 @@ bool GCS_MAVLINK_Tracker::set_home(const Location& loc, bool _lock) { return tracker.set_home(loc); } -void GCS_MAVLINK_Tracker::handleMessage(const mavlink_message_t &msg) +void GCS_MAVLINK_Tracker::handle_message(const mavlink_message_t &msg) { switch (msg.msgid) { @@ -610,7 +610,7 @@ mission_failed: } default: - handle_common_message(msg); + GCS_MAVLINK::handle_message(msg); break; } // end switch } // end handle mavlink diff --git a/AntennaTracker/GCS_Mavlink.h b/AntennaTracker/GCS_Mavlink.h index 38f7cdb483..6389a06cfd 100644 --- a/AntennaTracker/GCS_Mavlink.h +++ b/AntennaTracker/GCS_Mavlink.h @@ -37,7 +37,7 @@ private: void packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) override; void mavlink_check_target(const mavlink_message_t &msg); - void handleMessage(const mavlink_message_t &msg) override; + void handle_message(const mavlink_message_t &msg) override; bool handle_guided_request(AP_Mission::Mission_Command &cmd) override; void handle_set_attitude_target(const mavlink_message_t &msg);