Browse Source

Rover: GCS_MAVLink now uses Mission singleton

master
Peter Barker 6 years ago committed by Randy Mackay
parent
commit
0fa9f43815
  1. 5
      APMrover2/GCS_Mavlink.cpp
  2. 1
      APMrover2/GCS_Mavlink.h

5
APMrover2/GCS_Mavlink.cpp

@ -1222,11 +1222,6 @@ AP_VisualOdom *GCS_MAVLINK_Rover::get_visual_odom() const @@ -1222,11 +1222,6 @@ AP_VisualOdom *GCS_MAVLINK_Rover::get_visual_odom() const
#endif
}
AP_Mission *GCS_MAVLINK_Rover::get_mission()
{
return &rover.mission;
}
AP_Rally *GCS_MAVLINK_Rover::get_rally() const
{
#if AP_RALLY == ENABLED

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;
AP_Mission *get_mission() override;
AP_Rally *get_rally() const override;
AP_AdvancedFailsafe *get_advanced_failsafe() const override;
AP_VisualOdom *get_visual_odom() const override;

Loading…
Cancel
Save