GCS_MAVLink: move gcs_out_of_time into GCS object

This commit is contained in:
Peter Barker 2017-08-21 12:32:25 +10:00 committed by Francisco Ferreira
parent ed5d891730
commit b4e536b424

View File

@ -477,6 +477,13 @@ public:
void update();
virtual void setup_uarts(AP_SerialManager &serial_manager);
bool out_of_time() const {
return _out_of_time;
}
void set_out_of_time(bool val) {
_out_of_time = val;
}
/*
set a dataflash pointer for logging
*/
@ -515,6 +522,9 @@ private:
ObjectArray<statustext_t> _statustext_queue{_status_capacity};
// true if we are running short on time in our main loop
bool _out_of_time;
};
GCS &gcs();