diff --git a/libraries/AP_Logger/AP_Logger.cpp b/libraries/AP_Logger/AP_Logger.cpp
index 4d73572b05..3feec6f4f3 100644
--- a/libraries/AP_Logger/AP_Logger.cpp
+++ b/libraries/AP_Logger/AP_Logger.cpp
@@ -22,6 +22,10 @@ extern const AP_HAL::HAL& hal;
 #define HAL_LOGGING_MAV_BUFSIZE  8
 #endif 
 
+#ifndef HAL_LOGGING_FILE_TIMEOUT
+#define HAL_LOGGING_FILE_TIMEOUT 5
+#endif 
+
 // by default log for 15 seconds after disarming
 #ifndef HAL_LOGGER_ARM_PERSIST
 #define HAL_LOGGER_ARM_PERSIST 15
@@ -78,6 +82,13 @@ const AP_Param::GroupInfo AP_Logger::var_info[] = {
     // @Units: kB
     AP_GROUPINFO("_MAV_BUFSIZE",  5, AP_Logger, _params.mav_bufsize,       HAL_LOGGING_MAV_BUFSIZE),
 
+    // @Param: _FILE_TIMEOUT
+    // @DisplayName: Timeout before giving up on file writes
+    // @Description: This controls the amount of time before failing writes to a log file cause the file to be closed and logging stopped.
+    // @User: Standard
+    // @Units: s
+    AP_GROUPINFO("_FILE_TIMEOUT",  6, AP_Logger, _params.file_timeout,     HAL_LOGGING_FILE_TIMEOUT),
+    
     AP_GROUPEND
 };
 
diff --git a/libraries/AP_Logger/AP_Logger.h b/libraries/AP_Logger/AP_Logger.h
index 5a1483e834..08f2a5cb1b 100644
--- a/libraries/AP_Logger/AP_Logger.h
+++ b/libraries/AP_Logger/AP_Logger.h
@@ -329,6 +329,7 @@ public:
         AP_Int8 log_disarmed;
         AP_Int8 log_replay;
         AP_Int8 mav_bufsize; // in kilobytes
+        AP_Int16 file_timeout; // in seconds
     } _params;
 
     const struct LogStructure *structure(uint16_t num) const;
diff --git a/libraries/AP_Logger/AP_Logger_File.cpp b/libraries/AP_Logger/AP_Logger_File.cpp
index 9cdd7cc605..550635984e 100644
--- a/libraries/AP_Logger/AP_Logger_File.cpp
+++ b/libraries/AP_Logger/AP_Logger_File.cpp
@@ -808,7 +808,7 @@ uint16_t AP_Logger_File::start_new_log(void)
         _read_fd = -1;
     }
 
-    if (disk_space_avail() < _free_space_min_avail) {
+    if (disk_space_avail() < _free_space_min_avail && disk_space() > 0) {
         hal.console->printf("Out of space for logging\n");
         _open_error = true;
         return 0xffff;
@@ -941,7 +941,7 @@ void AP_Logger_File::_io_timer(void)
     if (tnow - _free_space_last_check_time > _free_space_check_interval) {
         _free_space_last_check_time = tnow;
         last_io_operation = "disk_space_avail";
-        if (disk_space_avail() < _free_space_min_avail) {
+        if (disk_space_avail() < _free_space_min_avail && disk_space() > 0) {
             hal.console->printf("Out of space for logging\n");
             stop_logging();
             _open_error = true; // prevent logging starting again
@@ -982,8 +982,8 @@ void AP_Logger_File::_io_timer(void)
     ssize_t nwritten = AP::FS().write(_write_fd, head, nbytes);
     last_io_operation = "";
     if (nwritten <= 0) {
-        if (tnow - _last_write_ms > 2000) {
-            // if we can't write for 2 seconds we give up and close
+        if ((tnow - _last_write_ms)/1000U > unsigned(_front._params.file_timeout)) {
+            // if we can't write for LOG_FILE_TIMEOUT seconds we give up and close
             // the file. This allows us to cope with temporary write
             // failures caused by directory listing
             hal.util->perf_count(_perf_errors);
@@ -994,7 +994,9 @@ void AP_Logger_File::_io_timer(void)
             _initialised = false;
             printf("Failed to write to File: %s\n", strerror(errno));
         }
+        _last_write_failed = true;
     } else {
+        _last_write_failed = false;
         _last_write_ms = tnow;
         _write_offset += nwritten;
         _writebuf.advance(nwritten);
@@ -1043,8 +1045,9 @@ bool AP_Logger_File::logging_enabled() const
 
 bool AP_Logger_File::io_thread_alive() const
 {
-    // if the io thread hasn't had a heartbeat in a full second then it is dead
-    return (AP_HAL::millis() - _io_timer_heartbeat) < 1000;
+    // if the io thread hasn't had a heartbeat in a full seconds then it is dead
+    // this is enough time for a sdcard remount
+    return (AP_HAL::millis() - _io_timer_heartbeat) < 3000U;
 }
 
 bool AP_Logger_File::logging_failed() const
@@ -1060,6 +1063,9 @@ bool AP_Logger_File::logging_failed() const
         // Good.
         return true;
     }
+    if (_last_write_failed) {
+        return true;
+    }
 
     return false;
 }
diff --git a/libraries/AP_Logger/AP_Logger_File.h b/libraries/AP_Logger/AP_Logger_File.h
index 0e3b390ed1..59f3fece8a 100644
--- a/libraries/AP_Logger/AP_Logger_File.h
+++ b/libraries/AP_Logger/AP_Logger_File.h
@@ -79,6 +79,7 @@ private:
     uint32_t _write_offset;
     volatile bool _open_error;
     const char *_log_directory;
+    bool _last_write_failed;
 
     uint32_t _io_timer_heartbeat;
     bool io_thread_alive() const;