mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
GCS_MAVLink: Use rally singleton
This commit is contained in:
parent
36cc66f0f3
commit
27d461348e
@ -284,7 +284,6 @@ protected:
|
||||
// overridable method to check for packet acceptance. Allows for
|
||||
// enforcement of GCS sysid
|
||||
bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg);
|
||||
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; }
|
||||
virtual bool set_mode(uint8_t mode) = 0;
|
||||
|
@ -24,8 +24,6 @@ class GCS_MAVLINK_Dummy : public GCS_MAVLINK
|
||||
|
||||
protected:
|
||||
|
||||
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; };
|
||||
|
||||
|
@ -19,7 +19,7 @@
|
||||
|
||||
void GCS_MAVLINK::handle_rally_point(mavlink_message_t *msg)
|
||||
{
|
||||
AP_Rally *r = get_rally();
|
||||
AP_Rally *r = AP::rally();
|
||||
if (r == nullptr) {
|
||||
return;
|
||||
}
|
||||
@ -58,7 +58,7 @@ void GCS_MAVLINK::handle_rally_point(mavlink_message_t *msg)
|
||||
|
||||
void GCS_MAVLINK::handle_rally_fetch_point(mavlink_message_t *msg)
|
||||
{
|
||||
AP_Rally *r = get_rally();
|
||||
AP_Rally *r = AP::rally();
|
||||
if (r == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
@ -30,7 +30,6 @@ public:
|
||||
protected:
|
||||
|
||||
uint32_t telem_delay() const override { return 0; }
|
||||
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
Block a user