diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 56fac55b13..272df1c70f 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1930,11 +1930,6 @@ void GCS_MAVLINK_Plane::handle_mission_set_current(AP_Mission &mission, mavlink_ } } -AP_GPS *GCS_MAVLINK_Plane::get_gps() const -{ - return &plane.gps; -} - AP_Camera *GCS_MAVLINK_Plane::get_camera() const { #if CAMERA == ENABLED diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index 998435e795..706ed7c77b 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -26,7 +26,6 @@ protected: AP_ServoRelayEvents *get_servorelayevents() const override; AP_AdvancedFailsafe *get_advanced_failsafe() const override; AP_Rally *get_rally() const override; - AP_GPS *get_gps() const override; const AP_FWVersion &get_fwver() const override; void set_ekf_origin(const Location& loc) override;