diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index f57a3122eb..af56422fdc 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -2132,6 +2132,7 @@ void Plane::mavlink_delay_cb() if (!gcs().chan(0).initialised || in_mavlink_delay) return; in_mavlink_delay = true; + DataFlash.EnableWrites(false); uint32_t tnow = millis(); if (tnow - last_1hz > 1000) { @@ -2150,6 +2151,7 @@ void Plane::mavlink_delay_cb() gcs_send_text(MAV_SEVERITY_INFO, "Initialising APM"); } + DataFlash.EnableWrites(true); in_mavlink_delay = false; } diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index 5e0e4b902c..3784e34940 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -85,9 +85,9 @@ int8_t Plane::dump_log(uint8_t argc, const Menu::arg *argv) int8_t Plane::erase_logs(uint8_t argc, const Menu::arg *argv) { - in_mavlink_delay = true; + DataFlash.EnableWrites(false); do_erase_logs(); - in_mavlink_delay = false; + DataFlash.EnableWrites(true); return 0; } diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 39c7888c1e..6b59c62f0b 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -835,9 +835,6 @@ void Plane::print_comma(void) bool Plane::should_log(uint32_t mask) { #if LOGGING_ENABLED == ENABLED - if (in_mavlink_delay) { - return false; - } if (!(mask & g.log_bitmask)) { return false; }