mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: use gps singleton for GCS functions
This commit is contained in:
parent
8f48b3187e
commit
b4294c00f6
@ -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
|
||||
|
@ -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…
Reference in New Issue
Block a user