mirror of https://github.com/ArduPilot/ardupilot
Tracker: use gps singleton for GCS functions
This commit is contained in:
parent
baf82cec22
commit
a6bda813f1
|
@ -771,11 +771,6 @@ void Tracker::gcs_retry_deferred(void)
|
|||
gcs().retry_deferred();
|
||||
}
|
||||
|
||||
AP_GPS *GCS_MAVLINK_Tracker::get_gps() const
|
||||
{
|
||||
return &tracker.gps;
|
||||
}
|
||||
|
||||
Compass *GCS_MAVLINK_Tracker::get_compass() const
|
||||
{
|
||||
return &tracker.compass;
|
||||
|
|
|
@ -21,7 +21,6 @@ protected:
|
|||
AP_Rally *get_rally() const override { return nullptr; };
|
||||
AP_Camera *get_camera() const override { return nullptr; };
|
||||
AP_ServoRelayEvents *get_servorelayevents() const override { return nullptr; }
|
||||
AP_GPS *get_gps() const override;
|
||||
const AP_FWVersion &get_fwver() const override;
|
||||
void set_ekf_origin(const Location& loc) override;
|
||||
|
||||
|
|
Loading…
Reference in New Issue