mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: use mission singleton
This commit is contained in:
parent
452382ff76
commit
dfd0ecd2bd
|
@ -279,7 +279,6 @@ protected:
|
|||
// overridable method to check for packet acceptance. Allows for
|
||||
// enforcement of GCS sysid
|
||||
virtual bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) { return true; }
|
||||
virtual AP_Mission *get_mission() = 0;
|
||||
virtual AP_Rally *get_rally() const = 0;
|
||||
virtual AP_AdvancedFailsafe *get_advanced_failsafe() const { return nullptr; };
|
||||
virtual AP_VisualOdom *get_visual_odom() const { return nullptr; }
|
||||
|
|
|
@ -2997,7 +2997,7 @@ void GCS_MAVLINK::handle_common_message(mavlink_message_t *msg)
|
|||
|
||||
void GCS_MAVLINK::handle_common_mission_message(mavlink_message_t *msg)
|
||||
{
|
||||
AP_Mission *_mission = get_mission();
|
||||
AP_Mission *_mission = AP::mission();
|
||||
if (_mission == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
@ -3527,7 +3527,7 @@ bool GCS_MAVLINK::try_send_compass_message(const enum ap_message id)
|
|||
|
||||
bool GCS_MAVLINK::try_send_mission_message(const enum ap_message id)
|
||||
{
|
||||
AP_Mission *mission = get_mission();
|
||||
AP_Mission *mission = AP::mission();
|
||||
if (mission == nullptr) {
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -24,7 +24,6 @@ class GCS_MAVLINK_Dummy : public GCS_MAVLINK
|
|||
|
||||
protected:
|
||||
|
||||
AP_Mission *get_mission() override { return nullptr; }
|
||||
AP_Rally *get_rally() const override { return nullptr; };
|
||||
|
||||
uint8_t sysid_my_gcs() const override { return 1; }
|
||||
|
|
|
@ -30,7 +30,6 @@ public:
|
|||
protected:
|
||||
|
||||
uint32_t telem_delay() const override { return 0; }
|
||||
AP_Mission *get_mission() override { return nullptr; }
|
||||
AP_Rally *get_rally() const override { return nullptr; }
|
||||
uint8_t sysid_my_gcs() const override { return 1; }
|
||||
bool set_mode(uint8_t mode) override { return false; };
|
||||
|
|
Loading…
Reference in New Issue