mirror of https://github.com/ArduPilot/ardupilot
Tracker: stop using in_mavlink_delay as a proxy for disabling logging
This commit is contained in:
parent
30dfd32b87
commit
31ac03368d
|
@ -889,6 +889,7 @@ void Tracker::mavlink_delay_cb()
|
|||
if (!gcs_chan[0].initialised) return;
|
||||
|
||||
tracker.in_mavlink_delay = true;
|
||||
DataFlash.EnableWrites(false);
|
||||
|
||||
uint32_t tnow = AP_HAL::millis();
|
||||
if (tnow - last_1hz > 1000) {
|
||||
|
@ -906,6 +907,7 @@ void Tracker::mavlink_delay_cb()
|
|||
last_5s = tnow;
|
||||
gcs_send_text(MAV_SEVERITY_INFO, "Initialising APM");
|
||||
}
|
||||
DataFlash.EnableWrites(true);
|
||||
tracker.in_mavlink_delay = false;
|
||||
}
|
||||
|
||||
|
|
|
@ -253,9 +253,6 @@ void Tracker::check_usb_mux(void)
|
|||
*/
|
||||
bool Tracker::should_log(uint32_t mask)
|
||||
{
|
||||
if (in_mavlink_delay) {
|
||||
return false;
|
||||
}
|
||||
if (!(mask & g.log_bitmask)) {
|
||||
return false;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue