mirror of https://github.com/ArduPilot/ardupilot
Copter: use gps singleton for GCS function
This commit is contained in:
parent
a6bda813f1
commit
8f48b3187e
|
@ -1769,11 +1769,6 @@ Compass *GCS_MAVLINK_Copter::get_compass() const
|
|||
return &copter.compass;
|
||||
}
|
||||
|
||||
AP_GPS *GCS_MAVLINK_Copter::get_gps() const
|
||||
{
|
||||
return &copter.gps;
|
||||
}
|
||||
|
||||
AP_Camera *GCS_MAVLINK_Copter::get_camera() const
|
||||
{
|
||||
#if CAMERA == ENABLED
|
||||
|
|
|
@ -23,7 +23,6 @@ protected:
|
|||
Compass *get_compass() const override;
|
||||
AP_Camera *get_camera() const override;
|
||||
AP_ServoRelayEvents *get_servorelayevents() const override;
|
||||
AP_GPS *get_gps() const override;
|
||||
MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override;
|
||||
AP_AdvancedFailsafe *get_advanced_failsafe() const override;
|
||||
const AP_FWVersion &get_fwver() const override;
|
||||
|
|
Loading…
Reference in New Issue