diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index da13017832..32d2e1f8d6 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -217,7 +217,7 @@ uint8_t GCS_MAVLINK_Sub::sysid_my_gcs() const return sub.g.sysid_my_gcs; } -bool GCS_MAVLINK_Sub::vehicle_initialised() const { +bool GCS_Sub::vehicle_initialised() const { return sub.ap.initialised; } diff --git a/ArduSub/GCS_Mavlink.h b/ArduSub/GCS_Mavlink.h index c724428af7..0792ed2329 100644 --- a/ArduSub/GCS_Mavlink.h +++ b/ArduSub/GCS_Mavlink.h @@ -30,8 +30,6 @@ protected: int32_t global_position_int_alt() const override; int32_t global_position_int_relative_alt() const override; - bool vehicle_initialised() const override; - bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED; bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED; diff --git a/ArduSub/GCS_Sub.h b/ArduSub/GCS_Sub.h index 859b91cdeb..7b79293962 100644 --- a/ArduSub/GCS_Sub.h +++ b/ArduSub/GCS_Sub.h @@ -25,6 +25,8 @@ public: uint32_t custom_mode() const override; MAV_TYPE frame_type() const override; + bool vehicle_initialised() const override; + private: GCS_MAVLINK_Sub _chan[MAVLINK_COMM_NUM_BUFFERS];