Browse Source

Rover: GCS_MAVLink uses compass singleton, stop implementing get_compass

mission-4.1.18
Peter Barker 7 years ago committed by Peter Barker
parent
commit
a5691500ad
  1. 5
      APMrover2/GCS_Mavlink.cpp
  2. 1
      APMrover2/GCS_Mavlink.h

5
APMrover2/GCS_Mavlink.cpp

@ -1295,11 +1295,6 @@ AP_VisualOdom *GCS_MAVLINK_Rover::get_visual_odom() const @@ -1295,11 +1295,6 @@ AP_VisualOdom *GCS_MAVLINK_Rover::get_visual_odom() const
#endif
}
Compass *GCS_MAVLINK_Rover::get_compass() const
{
return &rover.compass;
}
AP_Mission *GCS_MAVLINK_Rover::get_mission()
{
return &rover.mission;

1
APMrover2/GCS_Mavlink.h

@ -14,7 +14,6 @@ protected: @@ -14,7 +14,6 @@ protected:
uint32_t telem_delay() const override;
bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) override;
Compass *get_compass() const override;
AP_Mission *get_mission() override;
AP_Rally *get_rally() const override;
AP_Camera *get_camera() const override;

Loading…
Cancel
Save