mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: move vehicle_initialised to be on GCS not GCS_MAVLink
This commit is contained in:
parent
1a55f0ffab
commit
cf264a7d5e
|
@ -437,8 +437,6 @@ protected:
|
|||
void send_hwstatus();
|
||||
void handle_data_packet(mavlink_message_t *msg);
|
||||
|
||||
virtual bool vehicle_initialised() const { return true; }
|
||||
|
||||
// these two methods are called after current_loc is updated:
|
||||
virtual int32_t global_position_int_alt() const;
|
||||
virtual int32_t global_position_int_relative_alt() const;
|
||||
|
@ -776,6 +774,7 @@ public:
|
|||
void update_passthru();
|
||||
|
||||
void get_sensor_status_flags(uint32_t &present, uint32_t &enabled, uint32_t &health);
|
||||
virtual bool vehicle_initialised() const { return true; }
|
||||
|
||||
protected:
|
||||
|
||||
|
|
|
@ -198,7 +198,7 @@ void GCS_MAVLINK::send_meminfo(void)
|
|||
// report power supply status
|
||||
void GCS_MAVLINK::send_power_status(void)
|
||||
{
|
||||
if (!vehicle_initialised()) {
|
||||
if (!gcs().vehicle_initialised()) {
|
||||
// avoid unnecessary errors being reported to user
|
||||
return;
|
||||
}
|
||||
|
@ -3846,7 +3846,7 @@ void GCS_MAVLINK::send_sys_status()
|
|||
{
|
||||
// send extended status only once vehicle has been initialised
|
||||
// to avoid unnecessary errors being reported to user
|
||||
if (!vehicle_initialised()) {
|
||||
if (!gcs().vehicle_initialised()) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue