Rover: move vehicle_initialised to be on GCS not GCS_MAVLink

This commit is contained in:
Peter Barker 2019-03-01 22:50:14 +11:00 committed by Peter Barker
parent cf264a7d5e
commit 070b185d2a
3 changed files with 3 additions and 3 deletions

View File

@ -285,7 +285,7 @@ uint32_t GCS_MAVLINK_Rover::telem_delay() const
return static_cast<uint32_t>(rover.g.telem_delay);
}
bool GCS_MAVLINK_Rover::vehicle_initialised() const
bool GCS_Rover::vehicle_initialised() const
{
return rover.control_mode != &rover.mode_initializing;
}

View File

@ -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;

View File

@ -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: