diff --git a/src/modules/logger/log_writer.cpp b/src/modules/logger/log_writer.cpp
index e583942d5ca740eecc30de255e2c4495659e3ad5..0e900afd7a89a39d433d5ef47f57abce700c36b5 100644
--- a/src/modules/logger/log_writer.cpp
+++ b/src/modules/logger/log_writer.cpp
@@ -100,7 +100,7 @@ bool LogWriter::is_started() const
 	bool ret = false;
 
 	if (_log_writer_file) {
-		ret = _log_writer_file->is_started();
+		ret = _log_writer_file->is_started(LogType::Full);
 	}
 
 	if (_log_writer_mavlink) {
@@ -113,7 +113,7 @@ bool LogWriter::is_started() const
 bool LogWriter::is_started(Backend query_backend) const
 {
 	if (query_backend == BackendFile && _log_writer_file) {
-		return _log_writer_file->is_started();
+		return _log_writer_file->is_started(LogType::Full);
 	}
 
 	if (query_backend == BackendMavlink && _log_writer_mavlink) {
@@ -126,14 +126,14 @@ bool LogWriter::is_started(Backend query_backend) const
 void LogWriter::start_log_file(const char *filename)
 {
 	if (_log_writer_file) {
-		_log_writer_file->start_log(filename);
+		_log_writer_file->start_log(LogType::Full, filename);
 	}
 }
 
 void LogWriter::stop_log_file()
 {
 	if (_log_writer_file) {
-		_log_writer_file->stop_log();
+		_log_writer_file->stop_log(LogType::Full);
 	}
 }
 
@@ -163,7 +163,7 @@ int LogWriter::write_message(void *ptr, size_t size, uint64_t dropout_start)
 	int ret_file = 0, ret_mavlink = 0;
 
 	if (_log_writer_file_for_write) {
-		ret_file = _log_writer_file_for_write->write_message(ptr, size, dropout_start);
+		ret_file = _log_writer_file_for_write->write_message(LogType::Full, ptr, size, dropout_start);
 	}
 
 	if (_log_writer_mavlink_for_write) {
diff --git a/src/modules/logger/log_writer.h b/src/modules/logger/log_writer.h
index 1069a3ccb60410dcbd09fe25d3ec11f3dcbf3312..dc0fb1f4406a655c434810410e42c514301ec555 100644
--- a/src/modules/logger/log_writer.h
+++ b/src/modules/logger/log_writer.h
@@ -118,21 +118,21 @@ public:
 
 	size_t get_total_written_file() const
 	{
-		if (_log_writer_file) { return _log_writer_file->get_total_written(); }
+		if (_log_writer_file) { return _log_writer_file->get_total_written(LogType::Full); }
 
 		return 0;
 	}
 
 	size_t get_buffer_size_file() const
 	{
-		if (_log_writer_file) { return _log_writer_file->get_buffer_size(); }
+		if (_log_writer_file) { return _log_writer_file->get_buffer_size(LogType::Full); }
 
 		return 0;
 	}
 
 	size_t get_buffer_fill_count_file() const
 	{
-		if (_log_writer_file) { return _log_writer_file->get_buffer_fill_count(); }
+		if (_log_writer_file) { return _log_writer_file->get_buffer_fill_count(LogType::Full); }
 
 		return 0;
 	}
diff --git a/src/modules/logger/log_writer_file.cpp b/src/modules/logger/log_writer_file.cpp
index 66dd78dfe167699b7ff9becf536bad2824a5c9cc..81cde76b951190262d30deb8e455731c742e10a7 100644
--- a/src/modules/logger/log_writer_file.cpp
+++ b/src/modules/logger/log_writer_file.cpp
@@ -51,17 +51,21 @@ namespace logger
 {
 constexpr size_t LogWriterFile::_min_write_chunk;
 
-
-LogWriterFile::LogWriterFile(size_t buffer_size) :
+LogWriterFile::LogWriterFile(size_t buffer_size)
+	: _buffers{
 	//We always write larger chunks (orb messages) to the buffer, so the buffer
 	//needs to be larger than the minimum write chunk (300 is somewhat arbitrary)
-	_buffer_size(math::max(buffer_size, _min_write_chunk + 300))
+	{
+		math::max(buffer_size, _min_write_chunk + 300),
+		perf_alloc(PC_ELAPSED, "logger_sd_write"), perf_alloc(PC_ELAPSED, "logger_sd_fsync")},
+
+	{
+		300, // buffer size for the mission log (can be kept fairly small)
+		perf_alloc(PC_ELAPSED, "logger_sd_write_mission"), perf_alloc(PC_ELAPSED, "logger_sd_fsync_mission")}
+}
 {
 	pthread_mutex_init(&_mtx, nullptr);
 	pthread_cond_init(&_cv, nullptr);
-	/* allocate write performance counters */
-	_perf_write = perf_alloc(PC_ELAPSED, "logger_sd_write");
-	_perf_fsync = perf_alloc(PC_ELAPSED, "logger_sd_fsync");
 }
 
 bool LogWriterFile::init()
@@ -73,59 +77,26 @@ LogWriterFile::~LogWriterFile()
 {
 	pthread_mutex_destroy(&_mtx);
 	pthread_cond_destroy(&_cv);
-	perf_free(_perf_write);
-	perf_free(_perf_fsync);
-
-	if (_fd >= 0) {
-		::close(_fd);
-	}
-
-	if (_buffer) {
-		delete[] _buffer;
-	}
 }
 
-void LogWriterFile::start_log(const char *filename)
+void LogWriterFile::start_log(LogType type, const char *filename)
 {
-	// register the current file with the hardfault handler: if the system crashes,
-	// the hardfault handler will append the crash log to that file on the next reboot.
-	// Note that we don't deregister it when closing the log, so that crashes after disarming
-	// are appended as well (the same holds for crashes before arming, which can be a bit misleading)
-	int ret = hardfault_store_filename(filename);
-
-	if (ret) {
-		PX4_ERR("Failed to register ULog file to the hardfault handler (%i)", ret);
-	}
-
-	_fd = ::open(filename, O_CREAT | O_WRONLY, PX4_O_MODE_666);
-
-	if (_fd < 0) {
-		PX4_ERR("Can't open log file %s, errno: %d", filename, errno);
-		_should_run = false;
-		return;
-	}
-
-	if (_buffer == nullptr) {
-		_buffer = new uint8_t[_buffer_size];
-
-		if (_buffer == nullptr) {
-			PX4_ERR("Can't create log buffer");
-			::close(_fd);
-			_fd = -1;
-			_should_run = false;
-			return;
+	if (type == LogType::Full) {
+		// register the current file with the hardfault handler: if the system crashes,
+		// the hardfault handler will append the crash log to that file on the next reboot.
+		// Note that we don't deregister it when closing the log, so that crashes after disarming
+		// are appended as well (the same holds for crashes before arming, which can be a bit misleading)
+		int ret = hardfault_store_filename(filename);
+
+		if (ret) {
+			PX4_ERR("Failed to register ULog file to the hardfault handler (%i)", ret);
 		}
 	}
 
-	PX4_INFO("Opened log file: %s", filename);
-	_should_run = true;
-	_running = true;
-
-	// Clear buffer and counters
-	_head = 0;
-	_count = 0;
-	_total_written = 0;
-	notify();
+	if (_buffers[(int)type].start_log(filename)) {
+		PX4_INFO("Opened %s log file: %s", log_type_str(type), filename);
+		notify();
+	}
 }
 
 int LogWriterFile::hardfault_store_filename(const char *log_file)
@@ -160,9 +131,9 @@ int LogWriterFile::hardfault_store_filename(const char *log_file)
 	return 0;
 }
 
-void LogWriterFile::stop_log()
+void LogWriterFile::stop_log(LogType type)
 {
-	_should_run = false;
+	_buffers[(int)type]._should_run = false;
 	notify();
 }
 
@@ -188,7 +159,7 @@ void LogWriterFile::thread_stop()
 {
 	// this will terminate the main loop of the writer thread
 	_exit_thread = true;
-	_should_run = false;
+	_buffers[0]._should_run = _buffers[1]._should_run = false;
 
 	notify();
 
@@ -218,7 +189,7 @@ void LogWriterFile::run()
 			bool start = false;
 			pthread_mutex_lock(&_mtx);
 			pthread_cond_wait(&_cv, &_mtx);
-			start = _should_run;
+			start = _buffers[0]._should_run || _buffers[1]._should_run;
 			pthread_mutex_unlock(&_mtx);
 
 			if (start) {
@@ -234,95 +205,95 @@ void LogWriterFile::run()
 		int written = 0;
 		hrt_abstime last_fsync = hrt_absolute_time();
 
+		pthread_mutex_lock(&_mtx);
+
 		while (true) {
-			size_t available = 0;
-			void *read_ptr = nullptr;
-			bool is_part = false;
 
-			/* lock _buffer
-			 * wait for sufficient data, cycle on notify()
-			 */
-			pthread_mutex_lock(&_mtx);
+			const hrt_abstime now = hrt_absolute_time();
 
-			while (true) {
-				available = get_read_ptr(&read_ptr, &is_part);
+			/* call fsync periodically to minimize potential loss of data */
+			const bool call_fsync = ++poll_count >= 100 || now - last_fsync > 1_s;
 
-				/* if sufficient data available or partial read or terminating, exit this wait loop */
-				if ((available >= _min_write_chunk) || is_part || !_should_run) {
-					/* GOTO end of block */
-					break;
-				}
-
-				/* wait for a call to notify()
-				 * this call unlocks the mutex while waiting, and returns with the mutex locked
-				 */
-				pthread_cond_wait(&_cv, &_mtx);
+			if (call_fsync) {
+				last_fsync = now;
+				poll_count = 0;
 			}
 
-			pthread_mutex_unlock(&_mtx);
-			written = 0;
-
-			if (available > 0) {
-				perf_begin(_perf_write);
-				written = ::write(_fd, read_ptr, available);
-				perf_end(_perf_write);
-
-				const hrt_abstime now = hrt_absolute_time();
-
-				/* call fsync periodically to minimize potential loss of data */
-				if (++poll_count >= 100 || now - last_fsync > 1_s) {
-					perf_begin(_perf_fsync);
-					::fsync(_fd);
-					perf_end(_perf_fsync);
-					poll_count = 0;
-					last_fsync = now;
-				}
+			constexpr size_t min_available[(int)LogType::Count] = {
+				_min_write_chunk,
+				1 // For the mission log, write as soon as there is data available
+			};
 
-				if (written < 0) {
-					PX4_WARN("error writing log file");
-					_should_run = false;
-					/* GOTO end of block */
-					break;
-				}
+			/* Check all buffers for available data. Mission log is first to avoid drops */
+			int i = (int)LogType::Count - 1;
 
-				pthread_mutex_lock(&_mtx);
-				/* subtract bytes written from number in _buffer (_count -= written) */
-				mark_read(written);
-				pthread_mutex_unlock(&_mtx);
+			while (i >= 0) {
+				void *read_ptr;
+				bool is_part;
+				LogFileBuffer &buffer = _buffers[i];
+				size_t available = buffer.get_read_ptr(&read_ptr, &is_part);
 
-				_total_written += written;
-			}
+				/* if sufficient data available or partial read or terminating, write data */
+				if (available >= min_available[i] || is_part || (!buffer._should_run && available > 0)) {
+					pthread_mutex_unlock(&_mtx);
+
+					written = buffer.write_to_file(read_ptr, available, call_fsync);
 
-			if (!_should_run && written == static_cast<int>(available) && !is_part) {
-				// Stop only when all data written
-				_running = false;
-				_head = 0;
-				_count = 0;
+					/* buffer.mark_read() requires _mtx to be locked */
+					pthread_mutex_lock(&_mtx);
 
-				if (_fd >= 0) {
-					int res = ::close(_fd);
-					_fd = -1;
+					if (written >= 0) {
+						/* subtract bytes written from number in buffer (count -= written) */
+						buffer.mark_read(written);
 
-					if (res) {
-						PX4_WARN("error closing log file");
+						if (!buffer._should_run && written == static_cast<int>(available) && !is_part) {
+							/* Stop only when all data written */
+							buffer.close_file();
+						}
 
 					} else {
-						PX4_INFO("closed logfile, bytes written: %zu", _total_written);
+						PX4_ERR("write failed (%i)", errno);
+						buffer._should_run = false;
+						buffer.close_file();
 					}
+
+				} else if (call_fsync) {
+					buffer.fsync();
+
+				} else if (available == 0 && !buffer._should_run) {
+					buffer.close_file();
+				}
+
+				/* if split into 2 parts, write the second part immediately as well */
+				if (!is_part) {
+					--i;
 				}
+			}
 
+
+			if (_buffers[0].fd() < 0 && _buffers[1].fd() < 0) {
+				// stop when both files are closed
 				break;
 			}
+
+			/* Wait for a call to notify(), which indicates new data is available.
+			 * Note that at this point there could already be new data available (because of a longer write),
+			 * and calling pthread_cond_wait() will still wait for the next notify(). But this is generally
+			 * not an issue because notify() is called regularly. */
+			pthread_cond_wait(&_cv, &_mtx);
 		}
+
+		// go back to idle
+		pthread_mutex_unlock(&_mtx);
 	}
 }
 
-int LogWriterFile::write_message(void *ptr, size_t size, uint64_t dropout_start)
+int LogWriterFile::write_message(LogType type, void *ptr, size_t size, uint64_t dropout_start)
 {
 	if (_need_reliable_transfer) {
 		int ret;
 
-		while ((ret = write(ptr, size, dropout_start)) == -1) {
+		while ((ret = write(type, ptr, size, dropout_start)) == -1) {
 			unlock();
 			notify();
 			usleep(3000);
@@ -332,17 +303,17 @@ int LogWriterFile::write_message(void *ptr, size_t size, uint64_t dropout_start)
 		return ret;
 	}
 
-	return write(ptr, size, dropout_start);
+	return write(type, ptr, size, dropout_start);
 }
 
-int LogWriterFile::write(void *ptr, size_t size, uint64_t dropout_start)
+int LogWriterFile::write(LogType type, void *ptr, size_t size, uint64_t dropout_start)
 {
-	if (!is_started()) {
+	if (!is_started(type)) {
 		return 0;
 	}
 
 	// Bytes available to write
-	size_t available = _buffer_size - _count;
+	size_t available = _buffers[(int)type].available();
 	size_t dropout_size = 0;
 
 	if (dropout_start) {
@@ -358,14 +329,44 @@ int LogWriterFile::write(void *ptr, size_t size, uint64_t dropout_start)
 		//write dropout msg
 		ulog_message_dropout_s dropout_msg;
 		dropout_msg.duration = (uint16_t)(hrt_elapsed_time(&dropout_start) / 1000);
-		write_no_check(&dropout_msg, sizeof(dropout_msg));
+		_buffers[(int)type].write_no_check(&dropout_msg, sizeof(dropout_msg));
 	}
 
-	write_no_check(ptr, size);
+	_buffers[(int)type].write_no_check(ptr, size);
 	return 0;
 }
 
-void LogWriterFile::write_no_check(void *ptr, size_t size)
+const char *log_type_str(LogType type)
+{
+	switch (type) {
+	case LogType::Full: return "full";
+
+	case LogType::Mission: return "mission";
+
+	case LogType::Count: break;
+	}
+
+	return "unknown";
+}
+
+LogWriterFile::LogFileBuffer::LogFileBuffer(size_t buffer_size, perf_counter_t perf_write, perf_counter_t perf_fsync)
+	: _buffer_size(buffer_size), _perf_write(perf_write), _perf_fsync(perf_fsync)
+{
+}
+
+LogWriterFile::LogFileBuffer::~LogFileBuffer()
+{
+	if (_fd >= 0) {
+		close(_fd);
+	}
+
+	delete[] _buffer;
+
+	perf_free(_perf_write);
+	perf_free(_perf_fsync);
+}
+
+void LogWriterFile::LogFileBuffer::write_no_check(void *ptr, size_t size)
 {
 	size_t n = _buffer_size - _head;	// bytes to end of the buffer
 
@@ -387,7 +388,7 @@ void LogWriterFile::write_no_check(void *ptr, size_t size)
 	_count += size;
 }
 
-size_t LogWriterFile::get_read_ptr(void **ptr, bool *is_part)
+size_t LogWriterFile::LogFileBuffer::get_read_ptr(void **ptr, bool *is_part)
 {
 	// bytes available to read
 	int read_ptr = _head - _count;
@@ -405,5 +406,73 @@ size_t LogWriterFile::get_read_ptr(void **ptr, bool *is_part)
 	}
 }
 
+bool LogWriterFile::LogFileBuffer::start_log(const char *filename)
+{
+	_fd = ::open(filename, O_CREAT | O_WRONLY, PX4_O_MODE_666);
+
+	if (_fd < 0) {
+		PX4_ERR("Can't open log file %s, errno: %d", filename, errno);
+		return false;
+	}
+
+	if (_buffer == nullptr) {
+		_buffer = new uint8_t[_buffer_size];
+
+		if (_buffer == nullptr) {
+			PX4_ERR("Can't create log buffer");
+			::close(_fd);
+			_fd = -1;
+			return false;
+		}
+	}
+
+	// Clear buffer and counters
+	_head = 0;
+	_count = 0;
+	_total_written = 0;
+
+	_should_run = true;
+
+	return true;
+}
+
+void LogWriterFile::LogFileBuffer::fsync() const
+{
+	perf_begin(_perf_fsync);
+	::fsync(_fd);
+	perf_end(_perf_fsync);
+}
+
+ssize_t LogWriterFile::LogFileBuffer::write_to_file(const void *buffer, size_t size, bool call_fsync) const
+{
+	perf_begin(_perf_write);
+	ssize_t ret = ::write(_fd, buffer, size);
+	perf_end(_perf_write);
+
+	if (call_fsync) {
+		fsync();
+	}
+
+	return ret;
+}
+
+void LogWriterFile::LogFileBuffer::close_file()
+{
+	_head = 0;
+	_count = 0;
+
+	if (_fd >= 0) {
+		int res = close(_fd);
+		_fd = -1;
+
+		if (res) {
+			PX4_WARN("closing log file failed (%i)", errno);
+
+		} else {
+			PX4_INFO("closed logfile, bytes written: %zu", _total_written);
+		}
+	}
+}
+
 }
 }
diff --git a/src/modules/logger/log_writer_file.h b/src/modules/logger/log_writer_file.h
index 58e96136da79bbc3603821a70f9a2673eee66e82..af58c032a66f233d33ee3d3049f3f3c7737bc707 100644
--- a/src/modules/logger/log_writer_file.h
+++ b/src/modules/logger/log_writer_file.h
@@ -44,6 +44,19 @@ namespace px4
 namespace logger
 {
 
+/**
+ * @enum LogType
+ * Defines different log (file) types
+ */
+enum class LogType {
+	Full = 0, //!< Normal, full size log
+	Mission,  //!< reduced mission log (e.g. for geotagging)
+
+	Count
+};
+
+const char *log_type_str(LogType type);
+
 /**
  * @class LogWriterFile
  * Writes logging data to a file
@@ -64,14 +77,14 @@ public:
 
 	void thread_stop();
 
-	void start_log(const char *filename);
+	void start_log(LogType type, const char *filename);
 
-	void stop_log();
+	void stop_log(LogType type);
 
-	bool is_started() const { return _should_run; }
+	bool is_started(LogType type) const { return _buffers[(int)type]._should_run; }
 
 	/** @see LogWriter::write_message() */
-	int write_message(void *ptr, size_t size, uint64_t dropout_start = 0);
+	int write_message(LogType type, void *ptr, size_t size, uint64_t dropout_start = 0);
 
 	void lock()
 	{
@@ -88,19 +101,19 @@ public:
 		pthread_cond_broadcast(&_cv);
 	}
 
-	size_t get_total_written() const
+	size_t get_total_written(LogType type) const
 	{
-		return _total_written;
+		return _buffers[(int)type].total_written();
 	}
 
-	size_t get_buffer_size() const
+	size_t get_buffer_size(LogType type) const
 	{
-		return _buffer_size;
+		return _buffers[(int)type].buffer_size();
 	}
 
-	size_t get_buffer_fill_count() const
+	size_t get_buffer_fill_count(LogType type) const
 	{
-		return _count;
+		return _buffers[(int)type].count();
 	}
 
 	void set_need_reliable_transfer(bool need_reliable)
@@ -120,13 +133,6 @@ private:
 
 	void run();
 
-	size_t get_read_ptr(void **ptr, bool *is_part);
-
-	void mark_read(size_t n)
-	{
-		_count -= n;
-	}
-
 	/**
 	 * permanently store the ulog file name for the hardfault crash handler, so that it can
 	 * append crash logs to the last ulog file.
@@ -138,30 +144,62 @@ private:
 	/**
 	 * write w/o waiting/blocking
 	 */
-	int write(void *ptr, size_t size, uint64_t dropout_start);
-
-	/**
-	 * Write to the buffer but assuming there is enough space
-	 */
-	inline void write_no_check(void *ptr, size_t size);
+	int write(LogType type, void *ptr, size_t size, uint64_t dropout_start);
 
 	/* 512 didn't seem to work properly, 4096 should match the FAT cluster size */
 	static constexpr size_t	_min_write_chunk = 4096;
 
-	int			_fd = -1;
-	uint8_t 	*_buffer = nullptr;
-	const size_t	_buffer_size;
-	size_t			_head = 0; ///< next position to write to
-	size_t			_count = 0; ///< number of bytes in _buffer to be written
-	size_t		_total_written = 0;
-	bool		_should_run = false;
-	bool		_running = false;
+	class LogFileBuffer
+	{
+	public:
+		LogFileBuffer(size_t buffer_size, perf_counter_t perf_write, perf_counter_t perf_fsync);
+
+		~LogFileBuffer();
+
+		bool start_log(const char *filename);
+
+		void close_file();
+
+		size_t get_read_ptr(void **ptr, bool *is_part);
+
+		/**
+		 * Write to the buffer but assuming there is enough space
+		 */
+		inline void write_no_check(void *ptr, size_t size);
+
+		size_t available() const { return _buffer_size - _count; }
+
+		int fd() const { return _fd; }
+
+		inline ssize_t write_to_file(const void *buffer, size_t size, bool call_fsync) const;
+
+		inline void fsync() const;
+
+		void mark_read(size_t n) { _count -= n; _total_written += n; }
+
+		size_t total_written() const { return _total_written; }
+		size_t buffer_size() const { return _buffer_size; }
+		size_t count() const { return _count; }
+
+		bool _should_run = false;
+
+	private:
+		const size_t _buffer_size;
+		int	_fd = -1;
+		uint8_t *_buffer = nullptr;
+		size_t _head = 0; ///< next position to write to
+		size_t _count = 0; ///< number of bytes in _buffer to be written
+		size_t _total_written = 0;
+		perf_counter_t _perf_write;
+		perf_counter_t _perf_fsync;
+	};
+
+	LogFileBuffer _buffers[(int)LogType::Count];
+
 	bool 		_exit_thread = false;
 	bool		_need_reliable_transfer = false;
 	pthread_mutex_t		_mtx;
 	pthread_cond_t		_cv;
-	perf_counter_t _perf_write;
-	perf_counter_t _perf_fsync;
 	pthread_t _thread = 0;
 };