mirror of https://github.com/ArduPilot/ardupilot
Sub: move vehicle_initialised to be on GCS not GCS_MAVLink
This commit is contained in:
parent
a5c18ff8f5
commit
fabf0a10d5
|
@ -217,7 +217,7 @@ uint8_t GCS_MAVLINK_Sub::sysid_my_gcs() const
|
||||||
return sub.g.sysid_my_gcs;
|
return sub.g.sysid_my_gcs;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool GCS_MAVLINK_Sub::vehicle_initialised() const {
|
bool GCS_Sub::vehicle_initialised() const {
|
||||||
return sub.ap.initialised;
|
return sub.ap.initialised;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -30,8 +30,6 @@ protected:
|
||||||
int32_t global_position_int_alt() const override;
|
int32_t global_position_int_alt() const override;
|
||||||
int32_t global_position_int_relative_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_to_current_location(bool lock) override WARN_IF_UNUSED;
|
||||||
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
|
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
|
||||||
|
|
||||||
|
|
|
@ -25,6 +25,8 @@ public:
|
||||||
uint32_t custom_mode() const override;
|
uint32_t custom_mode() const override;
|
||||||
MAV_TYPE frame_type() const override;
|
MAV_TYPE frame_type() const override;
|
||||||
|
|
||||||
|
bool vehicle_initialised() const override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
GCS_MAVLINK_Sub _chan[MAVLINK_COMM_NUM_BUFFERS];
|
GCS_MAVLINK_Sub _chan[MAVLINK_COMM_NUM_BUFFERS];
|
||||||
|
|
Loading…
Reference in New Issue