diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 87e0923d9a..bb93486651 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -285,7 +285,7 @@ uint32_t GCS_MAVLINK_Rover::telem_delay() const return static_cast(rover.g.telem_delay); } -bool GCS_MAVLINK_Rover::vehicle_initialised() const +bool GCS_Rover::vehicle_initialised() const { return rover.control_mode != &rover.mode_initializing; } diff --git a/APMrover2/GCS_Mavlink.h b/APMrover2/GCS_Mavlink.h index 7d71ccac96..4bf250cade 100644 --- a/APMrover2/GCS_Mavlink.h +++ b/APMrover2/GCS_Mavlink.h @@ -28,8 +28,6 @@ protected: bool persist_streamrates() const override { return true; } - bool vehicle_initialised() const override; - bool set_home_to_current_location(bool lock) override; bool set_home(const Location& loc, bool lock) override; uint64_t capabilities() const override; diff --git a/APMrover2/GCS_Rover.h b/APMrover2/GCS_Rover.h index 88b30b8dc6..f7b9c294e6 100644 --- a/APMrover2/GCS_Rover.h +++ b/APMrover2/GCS_Rover.h @@ -20,6 +20,8 @@ public: uint32_t custom_mode() const override; MAV_TYPE frame_type() const override; + bool vehicle_initialised() const override; + void update_sensor_status_flags(void) override; private: