diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 35d799fc5a..db1faef33f 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -291,7 +291,6 @@ protected: // enforcement of GCS sysid bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg); 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; void set_ekf_origin(const Location& loc); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 534aef43df..bc76016818 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -24,6 +24,7 @@ #include #include #include +#include #include "GCS.h" @@ -2772,7 +2773,7 @@ void GCS_MAVLINK::handle_data_packet(mavlink_message_t *msg) void GCS_MAVLINK::handle_vision_position_delta(mavlink_message_t *msg) { - AP_VisualOdom *visual_odom = get_visual_odom(); + AP_VisualOdom *visual_odom = AP::visualodom(); if (visual_odom == nullptr) { return; }