mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
Rover: use gps singleton for GCS functions
This commit is contained in:
parent
269294754f
commit
baf82cec22
@ -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);
|
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
|
AP_Camera *GCS_MAVLINK_Rover::get_camera() const
|
||||||
{
|
{
|
||||||
#if CAMERA == ENABLED
|
#if CAMERA == ENABLED
|
||||||
|
@ -21,7 +21,6 @@ protected:
|
|||||||
AP_Rally *get_rally() const override { return nullptr; };
|
AP_Rally *get_rally() const override { return nullptr; };
|
||||||
AP_Camera *get_camera() const override;
|
AP_Camera *get_camera() const override;
|
||||||
AP_ServoRelayEvents *get_servorelayevents() const override;
|
AP_ServoRelayEvents *get_servorelayevents() const override;
|
||||||
AP_GPS *get_gps() const override;
|
|
||||||
AP_AdvancedFailsafe *get_advanced_failsafe() const override;
|
AP_AdvancedFailsafe *get_advanced_failsafe() const override;
|
||||||
const AP_FWVersion &get_fwver() const override;
|
const AP_FWVersion &get_fwver() const override;
|
||||||
void set_ekf_origin(const Location& loc) override;
|
void set_ekf_origin(const Location& loc) override;
|
||||||
|
Loading…
Reference in New Issue
Block a user