Browse Source

Plane: use gps singleton for GCS functions

master
Peter Barker 7 years ago committed by Francisco Ferreira
parent
commit
b4294c00f6
  1. 5
      ArduPlane/GCS_Mavlink.cpp
  2. 1
      ArduPlane/GCS_Mavlink.h

5
ArduPlane/GCS_Mavlink.cpp

@ -1930,11 +1930,6 @@ void GCS_MAVLINK_Plane::handle_mission_set_current(AP_Mission &mission, mavlink_ @@ -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

1
ArduPlane/GCS_Mavlink.h

@ -26,7 +26,6 @@ protected: @@ -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;

Loading…
Cancel
Save