mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: GCS_MAVLink uses compass singleton, stop implementing get_compass
This commit is contained in:
parent
ec52c22c7c
commit
558158c62a
@ -1596,11 +1596,6 @@ bool GCS_MAVLINK_Plane::accept_packet(const mavlink_status_t &status, mavlink_me
|
||||
return (msg.sysid == plane.g.sysid_my_gcs);
|
||||
}
|
||||
|
||||
Compass *GCS_MAVLINK_Plane::get_compass() const
|
||||
{
|
||||
return &plane.compass;
|
||||
}
|
||||
|
||||
AP_Mission *GCS_MAVLINK_Plane::get_mission()
|
||||
{
|
||||
return &plane.mission;
|
||||
|
@ -19,7 +19,6 @@ protected:
|
||||
AP_Mission *get_mission() override;
|
||||
void handle_mission_set_current(AP_Mission &mission, mavlink_message_t *msg) override;
|
||||
|
||||
Compass *get_compass() const override;
|
||||
AP_Camera *get_camera() const override;
|
||||
AP_AdvancedFailsafe *get_advanced_failsafe() const override;
|
||||
AP_Rally *get_rally() const override;
|
||||
|
Loading…
Reference in New Issue
Block a user