diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index dfdec3548a..fd9869325a 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1596,11 +1596,6 @@ bool GCS_MAVLINK_Plane::accept_packet(const mavlink_status_t &status, mavlink_me return (msg.sysid == plane.g.sysid_my_gcs); } -Compass *GCS_MAVLINK_Plane::get_compass() const -{ - return &plane.compass; -} - AP_Mission *GCS_MAVLINK_Plane::get_mission() { return &plane.mission; diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index 41c79721c7..5180712708 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -19,7 +19,6 @@ protected: AP_Mission *get_mission() override; void handle_mission_set_current(AP_Mission &mission, mavlink_message_t *msg) override; - Compass *get_compass() const override; AP_Camera *get_camera() const override; AP_AdvancedFailsafe *get_advanced_failsafe() const override; AP_Rally *get_rally() const override;