diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index bb6cd83120..aa6fbe65f4 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -1391,11 +1391,6 @@ bool GCS_MAVLINK_Rover::accept_packet(const mavlink_status_t &status, mavlink_me return (msg.sysid == rover.g.sysid_my_gcs); } -AP_GPS *GCS_MAVLINK_Rover::get_gps() const -{ - return &rover.gps; -} - AP_Camera *GCS_MAVLINK_Rover::get_camera() const { #if CAMERA == ENABLED diff --git a/APMrover2/GCS_Mavlink.h b/APMrover2/GCS_Mavlink.h index 5da8fa8211..f33cbb65e4 100644 --- a/APMrover2/GCS_Mavlink.h +++ b/APMrover2/GCS_Mavlink.h @@ -21,7 +21,6 @@ protected: AP_Rally *get_rally() const override { return nullptr; }; AP_Camera *get_camera() const override; AP_ServoRelayEvents *get_servorelayevents() const override; - AP_GPS *get_gps() const override; AP_AdvancedFailsafe *get_advanced_failsafe() const override; const AP_FWVersion &get_fwver() const override; void set_ekf_origin(const Location& loc) override;