Browse Source

Copter: GCS_MAVLink now uses Mission singleton

mission-4.1.18
Peter Barker 6 years ago committed by Randy Mackay
parent
commit
8ac5ee02ea
  1. 9
      ArduCopter/GCS_Mavlink.cpp
  2. 1
      ArduCopter/GCS_Mavlink.h

9
ArduCopter/GCS_Mavlink.cpp

@ -1469,15 +1469,6 @@ bool GCS_MAVLINK_Copter::accept_packet(const mavlink_status_t &status, mavlink_m @@ -1469,15 +1469,6 @@ bool GCS_MAVLINK_Copter::accept_packet(const mavlink_status_t &status, mavlink_m
return (msg.sysid == copter.g.sysid_my_gcs);
}
AP_Mission *GCS_MAVLINK_Copter::get_mission()
{
#if MODE_AUTO_ENABLED == ENABLED
return &copter.mode_auto.mission;
#else
return nullptr;
#endif
}
AP_AdvancedFailsafe *GCS_MAVLINK_Copter::get_advanced_failsafe() const
{
#if ADVANCED_FAILSAFE == ENABLED

1
ArduCopter/GCS_Mavlink.h

@ -16,7 +16,6 @@ protected: @@ -16,7 +16,6 @@ protected:
bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) override;
AP_Mission *get_mission() override;
AP_Rally *get_rally() const override;
MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override;
AP_AdvancedFailsafe *get_advanced_failsafe() const override;

Loading…
Cancel
Save