diff --git a/ArduCopter/GCS_Copter.h b/ArduCopter/GCS_Copter.h index cde308b539..19be2fc8b2 100644 --- a/ArduCopter/GCS_Copter.h +++ b/ArduCopter/GCS_Copter.h @@ -27,6 +27,8 @@ public: const char* frame_string() const override; + bool vehicle_initialised() const override; + private: GCS_MAVLINK_Copter _chan[MAVLINK_COMM_NUM_BUFFERS]; diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index f0999220bd..2fb5d2a1ce 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -208,7 +208,7 @@ uint32_t GCS_MAVLINK_Copter::telem_delay() const return (uint32_t)(copter.g.telem_delay); } -bool GCS_MAVLINK_Copter::vehicle_initialised() const { +bool GCS_Copter::vehicle_initialised() const { return copter.ap.initialised; } diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index ad4beae439..532dcc6d7e 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/GCS_Mavlink.h @@ -54,8 +54,6 @@ private: void handle_rc_channels_override(const mavlink_message_t *msg) override; bool try_send_message(enum ap_message id) override; - bool vehicle_initialised() const override; - void packetReceived(const mavlink_status_t &status, mavlink_message_t &msg) override;