diff --git a/src/modules/logger/log_writer.cpp b/src/modules/logger/log_writer.cpp
index 0e900afd7a89a39d433d5ef47f57abce700c36b5..5f68a98e280b48f5e9620b26b0e15817591bae0e 100644
--- a/src/modules/logger/log_writer.cpp
+++ b/src/modules/logger/log_writer.cpp
@@ -95,45 +95,45 @@ LogWriter::~LogWriter()
 	}
 }
 
-bool LogWriter::is_started() const
+bool LogWriter::is_started(LogType type) const
 {
 	bool ret = false;
 
 	if (_log_writer_file) {
-		ret = _log_writer_file->is_started(LogType::Full);
+		ret = _log_writer_file->is_started(type);
 	}
 
-	if (_log_writer_mavlink) {
+	if (_log_writer_mavlink && type == LogType::Full) {
 		ret = ret || _log_writer_mavlink->is_started();
 	}
 
 	return ret;
 }
 
-bool LogWriter::is_started(Backend query_backend) const
+bool LogWriter::is_started(LogType type, Backend query_backend) const
 {
 	if (query_backend == BackendFile && _log_writer_file) {
-		return _log_writer_file->is_started(LogType::Full);
+		return _log_writer_file->is_started(type);
 	}
 
-	if (query_backend == BackendMavlink && _log_writer_mavlink) {
+	if (query_backend == BackendMavlink && _log_writer_mavlink && type == LogType::Full) {
 		return _log_writer_mavlink->is_started();
 	}
 
 	return false;
 }
 
-void LogWriter::start_log_file(const char *filename)
+void LogWriter::start_log_file(LogType type, const char *filename)
 {
 	if (_log_writer_file) {
-		_log_writer_file->start_log(LogType::Full, filename);
+		_log_writer_file->start_log(type, filename);
 	}
 }
 
-void LogWriter::stop_log_file()
+void LogWriter::stop_log_file(LogType type)
 {
 	if (_log_writer_file) {
-		_log_writer_file->stop_log(LogType::Full);
+		_log_writer_file->stop_log(type);
 	}
 }
 
@@ -158,15 +158,15 @@ void LogWriter::thread_stop()
 	}
 }
 
-int LogWriter::write_message(void *ptr, size_t size, uint64_t dropout_start)
+int LogWriter::write_message(LogType type, 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(LogType::Full, ptr, size, dropout_start);
+		ret_file = _log_writer_file_for_write->write_message(type, ptr, size, dropout_start);
 	}
 
-	if (_log_writer_mavlink_for_write) {
+	if (_log_writer_mavlink_for_write && type == LogType::Full) {
 		ret_mavlink = _log_writer_mavlink_for_write->write_message(ptr, size);
 	}
 
diff --git a/src/modules/logger/log_writer.h b/src/modules/logger/log_writer.h
index dc0fb1f4406a655c434810410e42c514301ec555..7aa9c1241747b689b369bd3dbc977841907a8c48 100644
--- a/src/modules/logger/log_writer.h
+++ b/src/modules/logger/log_writer.h
@@ -65,9 +65,9 @@ public:
 	/** stop all running threads and wait for them to exit */
 	void thread_stop();
 
-	void start_log_file(const char *filename);
+	void start_log_file(LogType type, const char *filename);
 
-	void stop_log_file();
+	void stop_log_file(LogType type);
 
 	void start_log_mavlink();
 
@@ -76,20 +76,21 @@ public:
 	/**
 	 * whether logging is currently active or not (any of the selected backends).
 	 */
-	bool is_started() const;
+	bool is_started(LogType type) const;
 
 	/**
 	 * whether logging is currently active or not for a specific backend.
 	 */
-	bool is_started(Backend query_backend) const;
+	bool is_started(LogType type, Backend query_backend) const;
 
 	/**
 	 * Write a single ulog message (including header). The caller must call lock() before calling this.
 	 * @param dropout_start timestamp when lastest dropout occured. 0 if no dropout at the moment.
 	 * @return 0 on success (or if no logging started),
 	 *         -1 if not enough space in the buffer left (file backend), -2 mavlink backend failed
+	 *  add type -> pass through, but not to mavlink if mission log
 	 */
-	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);
 
 	/**
 	 * Select a backend, so that future calls to write_message() only write to the selected
@@ -116,23 +117,23 @@ public:
 		if (_log_writer_file) { _log_writer_file->notify(); }
 	}
 
-	size_t get_total_written_file() const
+	size_t get_total_written_file(LogType type) const
 	{
-		if (_log_writer_file) { return _log_writer_file->get_total_written(LogType::Full); }
+		if (_log_writer_file) { return _log_writer_file->get_total_written(type); }
 
 		return 0;
 	}
 
-	size_t get_buffer_size_file() const
+	size_t get_buffer_size_file(LogType type) const
 	{
-		if (_log_writer_file) { return _log_writer_file->get_buffer_size(LogType::Full); }
+		if (_log_writer_file) { return _log_writer_file->get_buffer_size(type); }
 
 		return 0;
 	}
 
-	size_t get_buffer_fill_count_file() const
+	size_t get_buffer_fill_count_file(LogType type) const
 	{
-		if (_log_writer_file) { return _log_writer_file->get_buffer_fill_count(LogType::Full); }
+		if (_log_writer_file) { return _log_writer_file->get_buffer_fill_count(type); }
 
 		return 0;
 	}
diff --git a/src/modules/logger/logger.cpp b/src/modules/logger/logger.cpp
index 69c8d1a81c8f4967d06b4fd7be631d8e3f1074b4..1be2f50838979c34183ef9a34a89435f104ecff3 100644
--- a/src/modules/logger/logger.cpp
+++ b/src/modules/logger/logger.cpp
@@ -133,6 +133,8 @@ namespace px4
 namespace logger
 {
 
+constexpr const char *Logger::LOG_ROOT[(int)LogType::Count];
+
 int Logger::custom_command(int argc, char *argv[])
 {
 	if (!is_running()) {
@@ -172,13 +174,19 @@ It supports 2 backends:
 
 Both backends can be enabled and used at the same time.
 
+The file backend supports 2 types of log files: full (the normal log) and a mission
+log. The mission log is a reduced ulog file and can be used for example for geotagging or
+vehicle management. It can be enabled and configured via SDLOG_MISSION parameter.
+The normal log is always a superset of the mission log.
+
 ### Implementation
 The implementation uses two threads:
 - The main thread, running at a fixed rate (or polling on a topic if started with -p) and checking for
   data updates
 - The writer thread, writing data to the file
 
-In between there is a write buffer with configurable size. It should be large to avoid dropouts.
+In between there is a write buffer with configurable size (and another fixed-size buffer for
+the mission log). It should be large to avoid dropouts.
 
 ### Examples
 Typical usage to start logging immediately:
@@ -228,14 +236,20 @@ int Logger::print_status()
 	PX4_INFO("Running in mode: %s", configured_backend_mode());
 
 	bool is_logging = false;
-	if (_writer.is_started(LogWriter::BackendFile)) {
-		PX4_INFO("File Logging Running");
-		print_statistics();
+	if (_writer.is_started(LogType::Full, LogWriter::BackendFile)) {
+		PX4_INFO("Full File Logging Running:");
+		print_statistics(LogType::Full);
+		is_logging = true;
+	}
+
+	if (_writer.is_started(LogType::Mission, LogWriter::BackendFile)) {
+		PX4_INFO("Mission File Logging Running:");
+		print_statistics(LogType::Mission);
 		is_logging = true;
 	}
 
-	if (_writer.is_started(LogWriter::BackendMavlink)) {
-		PX4_INFO("Mavlink Logging Running");
+	if (_writer.is_started(LogType::Full, LogWriter::BackendMavlink)) {
+		PX4_INFO("Mavlink Logging Running (Full log)");
 		is_logging = true;
 	}
 
@@ -246,24 +260,29 @@ int Logger::print_status()
 	return 0;
 }
 
-void Logger::print_statistics()
+void Logger::print_statistics(LogType type)
 {
-	if (!_writer.is_started(LogWriter::BackendFile)) { //currently only statistics for file logging
+	if (!_writer.is_started(type, LogWriter::BackendFile)) { //currently only statistics for file logging
 		return;
 	}
+	Statistics &stats = _statistics[(int)type];
 
 	/* this is only for the file backend */
-	float kibibytes = _writer.get_total_written_file() / 1024.0f;
+	float kibibytes = _writer.get_total_written_file(type) / 1024.0f;
 	float mebibytes = kibibytes / 1024.0f;
-	float seconds = ((float)(hrt_absolute_time() - _start_time_file)) / 1000000.0f;
+	float seconds = ((float)(hrt_absolute_time() - stats.start_time_file)) / 1000000.0f;
 
-	PX4_INFO("Log file: %s/%s", _log_dir, _log_file_name);
-	PX4_INFO("Wrote %4.2f MiB (avg %5.2f KiB/s)", (double)mebibytes, (double)(kibibytes / seconds));
+	PX4_INFO("Log file: %s/%s/%s", LOG_ROOT[(int)type], _file_name[(int)type].log_dir, _file_name[(int)type].log_file_name);
+	if (mebibytes < 0.1f) {
+		PX4_INFO("Wrote %4.2f KiB (avg %5.2f KiB/s)", (double)kibibytes, (double)(kibibytes / seconds));
+	} else {
+		PX4_INFO("Wrote %4.2f MiB (avg %5.2f KiB/s)", (double)mebibytes, (double)(kibibytes / seconds));
+	}
 	PX4_INFO("Since last status: dropouts: %zu (max len: %.3f s), max used buffer: %zu / %zu B",
-		 _write_dropouts, (double)_max_dropout_duration, _high_water, _writer.get_buffer_size_file());
-	_high_water = 0;
-	_write_dropouts = 0;
-	_max_dropout_duration = 0.f;
+		 stats.write_dropouts, (double)stats.max_dropout_duration, stats.high_water, _writer.get_buffer_size_file(type));
+	stats.high_water = 0;
+	stats.write_dropouts = 0;
+	stats.max_dropout_duration = 0.f;
 }
 
 Logger *Logger::instantiate(int argc, char *argv[])
@@ -406,6 +425,7 @@ Logger::Logger(LogWriter::Backend backend, size_t buffer_size, uint32_t log_inte
 	_log_utc_offset = param_find("SDLOG_UTC_OFFSET");
 	_log_dirs_max = param_find("SDLOG_DIRS_MAX");
 	_sdlog_profile_handle = param_find("SDLOG_PROFILE");
+	_mission_log = param_find("SDLOG_MISSION");
 
 	if (poll_topic_name) {
 		const orb_metadata *const*topics = orb_get_topics();
@@ -527,16 +547,20 @@ bool Logger::add_topic(const char *name, unsigned interval)
 	return subscription;
 }
 
-bool Logger::copy_if_updated_multi(LoggerSubscription &sub, int multi_instance, void *buffer, bool try_to_subscribe)
+bool Logger::copy_if_updated_multi(int sub_idx, int multi_instance, void *buffer, bool try_to_subscribe)
 {
 	bool updated = false;
+	LoggerSubscription &sub = _subscriptions[sub_idx];
 	int &handle = sub.fd[multi_instance];
 
 	if (handle < 0 && try_to_subscribe) {
 
 		if (try_to_subscribe_topic(sub, multi_instance)) {
 
-			write_add_logged_msg(sub, multi_instance);
+			write_add_logged_msg(LogType::Full, sub, multi_instance);
+			if (sub_idx < _num_mission_subs) {
+				write_add_logged_msg(LogType::Mission, sub, multi_instance);
+			}
 
 			/* copy first data */
 			if (orb_copy(sub.metadata, handle, buffer) == PX4_OK) {
@@ -789,6 +813,19 @@ const char *Logger::configured_backend_mode() const
 	default: return "several";
 	}
 }
+
+void Logger::initialize_mission_topics(MissionLogType type)
+{
+	if (type == MissionLogType::Complete) {
+		add_mission_topic("camera_capture");
+		add_mission_topic("mission_result");
+		add_mission_topic("vehicle_global_position", 1000);
+		add_mission_topic("vehicle_status", 1000);
+	} else if (type == MissionLogType::Geotagging) {
+		add_mission_topic("camera_capture");
+	}
+}
+
 void Logger::initialize_configured_topics()
 {
 	// get the logging profile
@@ -833,6 +870,20 @@ void Logger::initialize_configured_topics()
 	}
 }
 
+
+void Logger::add_mission_topic(const char* name, unsigned interval)
+{
+	if (_num_mission_subs >= MAX_MISSION_TOPICS_NUM) {
+		PX4_ERR("Max num mission topics exceeded");
+		return;
+	}
+	if(add_topic(name, interval)) {
+		_mission_subscriptions[_num_mission_subs].min_delta_ms = interval;
+		_mission_subscriptions[_num_mission_subs].next_write_time = 0;
+		++_num_mission_subs;
+	}
+}
+
 void Logger::run()
 {
 #ifdef DBGPRINT
@@ -842,13 +893,13 @@ void Logger::run()
 	PX4_INFO("logger started (mode=%s)", configured_backend_mode());
 
 	if (_writer.backend() & LogWriter::BackendFile) {
-		int mkdir_ret = mkdir(LOG_ROOT, S_IRWXU | S_IRWXG | S_IRWXO);
+		int mkdir_ret = mkdir(LOG_ROOT[(int)LogType::Full], S_IRWXU | S_IRWXG | S_IRWXO);
 
 		if (mkdir_ret == 0) {
-			PX4_INFO("log root dir created: %s", LOG_ROOT);
+			PX4_INFO("log root dir created: %s", LOG_ROOT[(int)LogType::Full]);
 
 		} else if (errno != EEXIST) {
-			PX4_ERR("failed creating log root dir: %s", LOG_ROOT);
+			PX4_ERR("failed creating log root dir: %s (%i)", LOG_ROOT[(int)LogType::Full], errno);
 
 			if ((_writer.backend() & ~LogWriter::BackendFile) == 0) {
 				return;
@@ -861,7 +912,8 @@ void Logger::run()
 			param_get(_log_dirs_max, &max_log_dirs_to_keep);
 		}
 
-		if (util::check_free_space(LOG_ROOT, max_log_dirs_to_keep, _mavlink_log_pub, _sess_dir_index) == 1) {
+		if (util::check_free_space(LOG_ROOT[(int)LogType::Full], max_log_dirs_to_keep, _mavlink_log_pub,
+				_file_name[(int)LogType::Full].sess_dir_index) == 1) {
 			return;
 		}
 	}
@@ -871,6 +923,20 @@ void Logger::run()
 	int log_message_sub = orb_subscribe(ORB_ID(log_message));
 	orb_set_interval(log_message_sub, 20);
 
+	// mission log topics if enabled (must be added first)
+	int32_t mission_log_mode = 0;
+
+	if (_mission_log != PARAM_INVALID) {
+		param_get(_mission_log, &mission_log_mode);
+		initialize_mission_topics((MissionLogType)mission_log_mode);
+
+		if (_num_mission_subs > 0) {
+			int mkdir_ret = mkdir(LOG_ROOT[(int)LogType::Mission], S_IRWXU | S_IRWXG | S_IRWXO);
+			if (mkdir_ret != 0 && errno != EEXIST) {
+				PX4_ERR("failed creating log root dir: %s (%i)", LOG_ROOT[(int)LogType::Mission], errno);
+			}
+		}
+	}
 
 	int ntopics = add_topics_from_file(PX4_STORAGEDIR "/etc/logging/logger_topics.txt");
 
@@ -939,7 +1005,7 @@ void Logger::run()
 	// we start logging immediately
 	// the case where we wait with logging until vehicle is armed is handled below
 	if (_log_on_start) {
-		start_log_file();
+		start_log_file(LogType::Full);
 	}
 
 	/* init the update timer */
@@ -980,7 +1046,7 @@ void Logger::run()
 	while (!should_exit()) {
 
 		// Start/stop logging when system arm/disarm
-		const bool logging_started = check_arming_state(vehicle_status_sub);
+		const bool logging_started = check_arming_state(vehicle_status_sub, (MissionLogType)mission_log_mode);
 		if (logging_started) {
 #ifdef DBGPRINT
 			timer_start = hrt_absolute_time();
@@ -1002,20 +1068,17 @@ void Logger::run()
 
 		const hrt_abstime loop_time = hrt_absolute_time();
 
-		if (_writer.is_started()) {
+		if (_writer.is_started(LogType::Full)) { // mission log only runs when full log is also started
 
 			/* check if we need to output the process load */
 			if (_next_load_print != 0 && loop_time >= _next_load_print) {
 				_next_load_print = 0;
+				write_load_output();
 
 				if (_should_stop_file_log) {
 					_should_stop_file_log = false;
-					write_load_output();
-					stop_log_file();
+					stop_log_file(LogType::Full);
 					continue; // skip to next loop iteration
-
-				} else {
-					write_load_output();
 				}
 			}
 
@@ -1024,7 +1087,7 @@ void Logger::run()
 			/* Check if parameters have changed */
 			if (!_should_stop_file_log) { // do not record param changes after disarming
 				if (parameter_update_sub.update()) {
-					write_changed_parameters();
+					write_changed_parameters(LogType::Full);
 				}
 			}
 
@@ -1042,7 +1105,7 @@ void Logger::run()
 				 * and write a message to the log
 				 */
 				for (int instance = 0; instance < ORB_MULTI_MAX_INSTANCES; instance++) {
-					if (copy_if_updated_multi(sub, instance, _msg_buffer + sizeof(ulog_message_data_header_s),
+					if (copy_if_updated_multi(sub_idx, instance, _msg_buffer + sizeof(ulog_message_data_header_s),
 								  sub_idx == next_subscribe_topic_index)) {
 
 						uint16_t write_msg_size = static_cast<uint16_t>(msg_size - ULOG_MSG_HEADER_LEN);
@@ -1056,16 +1119,29 @@ void Logger::run()
 
 						//PX4_INFO("topic: %s, size = %zu, out_size = %zu", sub.metadata->o_name, sub.metadata->o_size, msg_size);
 
-						if (write_message(_msg_buffer, msg_size)) {
+						// full log
+						if (write_message(LogType::Full, _msg_buffer, msg_size)) {
 
 #ifdef DBGPRINT
 							total_bytes += msg_size;
 #endif /* DBGPRINT */
 
 							data_written = true;
+						}
 
-						} else {
-							break;	// Write buffer overflow, skip this record
+						// mission log
+						if (sub_idx < _num_mission_subs) {
+							if (_writer.is_started(LogType::Mission)) {
+								if (_mission_subscriptions[sub_idx].next_write_time < (loop_time / 100000)) {
+									unsigned delta_time = _mission_subscriptions[sub_idx].min_delta_ms;
+									if (delta_time > 0) {
+										_mission_subscriptions[sub_idx].next_write_time = (loop_time / 100000) + delta_time / 100;
+									}
+									if (write_message(LogType::Mission, _msg_buffer, msg_size)) {
+										data_written = true;
+									}
+								}
+							}
 						}
 					}
 				}
@@ -1093,12 +1169,15 @@ void Logger::run()
 					memcpy(_msg_buffer + 4, &log_message.timestamp, sizeof(ulog_message_logging_s::timestamp));
 					strncpy((char *)(_msg_buffer + 12), message, sizeof(ulog_message_logging_s::message));
 
-					write_message(_msg_buffer, write_msg_size + ULOG_MSG_HEADER_LEN);
+					write_message(LogType::Full, _msg_buffer, write_msg_size + ULOG_MSG_HEADER_LEN);
 				}
 			}
 
-			if (!_dropout_start && _writer.get_buffer_fill_count_file() > _high_water) {
-				_high_water = _writer.get_buffer_fill_count_file();
+			// update buffer statistics
+			for (int i = 0; i < (int)LogType::Count; ++i) {
+				if (!_statistics[i].dropout_start && _writer.get_buffer_fill_count_file((LogType)i) > _statistics[i].high_water) {
+					_statistics[i].high_water = _writer.get_buffer_fill_count_file((LogType)i);
+				}
 			}
 
 			/* release the log buffer */
@@ -1127,11 +1206,11 @@ void Logger::run()
 				alloc_info = mallinfo();
 				double throughput = total_bytes / deltat;
 				PX4_INFO("%8.1f kB/s, %zu highWater,  %d dropouts, %5.3f sec max, free heap: %d",
-					 throughput / 1.e3, _high_water, _write_dropouts, (double)_max_dropout_duration,
+					 throughput / 1.e3, _statistics[0].high_water, _statistics[0].write_dropouts, (double)_statistics[0].max_dropout_duration,
 					 alloc_info.fordblks);
 
-				_high_water = 0;
-				_max_dropout_duration = 0.f;
+				_statistics[0].high_water = 0;
+				_statistics[0].max_dropout_duration = 0.f;
 				total_bytes = 0;
 				timer_start = hrt_absolute_time();
 			}
@@ -1171,7 +1250,7 @@ void Logger::run()
 
 			} else if (pret != 0) {
 				if (fds[0].revents & POLLIN) {
-					// need to to an orb_copy so that poll will not return immediately
+					// need to to an orb_copy so that the next poll will not return immediately
 					orb_copy(_polling_topic_meta, polling_topic_sub, _msg_buffer);
 				}
 			}
@@ -1188,7 +1267,8 @@ void Logger::run()
 		}
 	}
 
-	stop_log_file();
+	stop_log_file(LogType::Full);
+	stop_log_file(LogType::Mission);
 
 	hrt_cancel(&timer_call);
 	px4_sem_destroy(&timer_callback_data.semaphore);
@@ -1226,7 +1306,7 @@ void Logger::run()
 	px4_unregister_shutdown_hook(&Logger::request_stop_static);
 }
 
-bool Logger::check_arming_state(int vehicle_status_sub)
+bool Logger::check_arming_state(int vehicle_status_sub, MissionLogType mission_log_type)
 {
 	bool vehicle_status_updated;
 	int ret = orb_check(vehicle_status_sub, &vehicle_status_updated);
@@ -1244,16 +1324,24 @@ bool Logger::check_arming_state(int vehicle_status_sub)
 
 				if (_should_stop_file_log) { // happens on quick arming after disarm
 					_should_stop_file_log = false;
-					stop_log_file();
+					stop_log_file(LogType::Full);
 				}
 
-				start_log_file();
+				start_log_file(LogType::Full);
 				bret = true;
 
+				if (mission_log_type != MissionLogType::Disabled) {
+					start_log_file(LogType::Mission);
+				}
+
 			} else {
 				// delayed stop: we measure the process loads and then stop
 				initialize_load_output(PrintLoadReason::Postflight);
 				_should_stop_file_log = true;
+
+				if (mission_log_type != MissionLogType::Disabled) {
+					stop_log_file(LogType::Mission);
+				}
 			}
 		}
 	}
@@ -1292,74 +1380,81 @@ void Logger::handle_vehicle_command_update(int vehicle_command_sub, orb_advert_t
 	}
 }
 
-bool Logger::write_message(void *ptr, size_t size)
+bool Logger::write_message(LogType type, void *ptr, size_t size)
 {
-	if (_writer.write_message(ptr, size, _dropout_start) != -1) {
+	Statistics &stats = _statistics[(int)type];
+	if (_writer.write_message(type, ptr, size, stats.dropout_start) != -1) {
 
-		if (_dropout_start) {
-			float dropout_duration = (float)(hrt_elapsed_time(&_dropout_start) / 1000) / 1.e3f;
+		if (stats.dropout_start) {
+			float dropout_duration = (float)(hrt_elapsed_time(&stats.dropout_start) / 1000) / 1.e3f;
 
-			if (dropout_duration > _max_dropout_duration) {
-				_max_dropout_duration = dropout_duration;
+			if (dropout_duration > stats.max_dropout_duration) {
+				stats.max_dropout_duration = dropout_duration;
 			}
 
-			_dropout_start = 0;
+			stats.dropout_start = 0;
 		}
 
 		return true;
 	}
 
-	if (!_dropout_start) {
-		_dropout_start = hrt_absolute_time();
-		++_write_dropouts;
-		_high_water = 0;
+	if (!stats.dropout_start) {
+		stats.dropout_start = hrt_absolute_time();
+		++stats.write_dropouts;
+		stats.high_water = 0;
 	}
 
 	return false;
 }
 
-int Logger::create_log_dir(tm *tt)
+int Logger::create_log_dir(LogType type, tm *tt, char *log_dir, int log_dir_len)
 {
-	/* create dir on sdcard if needed */
-	int mkdir_ret;
+	LogFileName& file_name = _file_name[(int)type];
 
-	if (tt) {
-		int n = snprintf(_log_dir, sizeof(_log_dir), "%s/", LOG_ROOT);
+	/* create dir on sdcard if needed */
+	int n = snprintf(log_dir, log_dir_len, "%s/", LOG_ROOT[(int)type]);
 
-		if (n >= (int)sizeof(_log_dir)) {
-			PX4_ERR("log path too long");
-			return -1;
-		}
+	if (n >= log_dir_len) {
+		PX4_ERR("log path too long");
+		return -1;
+	}
 
-		strftime(_log_dir + n, sizeof(_log_dir) - n, "%Y-%m-%d", tt);
-		mkdir_ret = mkdir(_log_dir, S_IRWXU | S_IRWXG | S_IRWXO);
+	if (tt) {
+		strftime(file_name.log_dir, sizeof(LogFileName::log_dir), "%Y-%m-%d", tt);
+		strncpy(log_dir + n, file_name.log_dir, log_dir_len - n);
+		int mkdir_ret = mkdir(log_dir, S_IRWXU | S_IRWXG | S_IRWXO);
 
 		if (mkdir_ret != OK && errno != EEXIST) {
-			PX4_ERR("failed creating new dir: %s", _log_dir);
+			PX4_ERR("failed creating new dir: %s", log_dir);
 			return -1;
 		}
 
 	} else {
-		uint16_t dir_number = _sess_dir_index;
+		uint16_t dir_number = file_name.sess_dir_index;
+
+		if (file_name.has_log_dir) {
+			strncpy(log_dir + n, file_name.log_dir, log_dir_len - n);
+		}
 
 		/* look for the next dir that does not exist */
-		while (!_has_log_dir) {
-			/* format log dir: e.g. /fs/microsd/sess001 */
-			int n = snprintf(_log_dir, sizeof(_log_dir), "%s/sess%03u", LOG_ROOT, dir_number);
+		while (!file_name.has_log_dir) {
+			/* format log dir: e.g. /fs/microsd/log/sess001 */
+			int n2 = snprintf(file_name.log_dir, sizeof(LogFileName::log_dir), "sess%03u", dir_number);
 
-			if (n >= (int)sizeof(_log_dir)) {
+			if (n2 >= (int)sizeof(LogFileName::log_dir)) {
 				PX4_ERR("log path too long (%i)", n);
 				return -1;
 			}
 
-			mkdir_ret = mkdir(_log_dir, S_IRWXU | S_IRWXG | S_IRWXO);
+			strncpy(log_dir + n, file_name.log_dir, log_dir_len - n);
+			int mkdir_ret = mkdir(log_dir, S_IRWXU | S_IRWXG | S_IRWXO);
 
 			if (mkdir_ret == 0) {
-				PX4_DEBUG("log dir created: %s", _log_dir);
-				_has_log_dir = true;
+				PX4_DEBUG("log dir created: %s", log_dir);
+				file_name.has_log_dir = true;
 
 			} else if (errno != EEXIST) {
-				PX4_ERR("failed creating new dir: %s (%i)", _log_dir, errno);
+				PX4_ERR("failed creating new dir: %s (%i)", log_dir, errno);
 				return -1;
 			}
 
@@ -1367,13 +1462,13 @@ int Logger::create_log_dir(tm *tt)
 			dir_number++;
 		}
 
-		_has_log_dir = true;
+		file_name.has_log_dir = true;
 	}
 
-	return 0;
+	return strlen(log_dir);
 }
 
-int Logger::get_log_file_name(char *file_name, size_t file_name_size)
+int Logger::get_log_file_name(LogType type, char *file_name, size_t file_name_size)
 {
 	tm tt = {};
 	bool time_ok = false;
@@ -1385,7 +1480,7 @@ int Logger::get_log_file_name(char *file_name, size_t file_name_size)
 			param_get(_log_utc_offset, &utc_offset);
 		}
 
-		/* use RTC time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.ulg */
+		/* use RTC time for log file naming, e.g. /fs/microsd/log/2014-01-19/19_37_52.ulg */
 		time_ok = util::get_log_time(&tt, utc_offset * 60, false);
 	}
 
@@ -1395,19 +1490,22 @@ int Logger::get_log_file_name(char *file_name, size_t file_name_size)
 		replay_suffix = "_replayed";
 	}
 
+	char *log_file_name = _file_name[(int)type].log_file_name;
 
 	if (time_ok) {
-		if (create_log_dir(&tt)) {
+		int n = create_log_dir(type, &tt, file_name, file_name_size);
+		if (n < 0) {
 			return -1;
 		}
 
 		char log_file_name_time[16] = "";
 		strftime(log_file_name_time, sizeof(log_file_name_time), "%H_%M_%S", &tt);
-		snprintf(_log_file_name, sizeof(_log_file_name), "%s%s.ulg", log_file_name_time, replay_suffix);
-		snprintf(file_name, file_name_size, "%s/%s", _log_dir, _log_file_name);
+		snprintf(log_file_name, sizeof(LogFileName::log_file_name), "%s%s.ulg", log_file_name_time, replay_suffix);
+		snprintf(file_name + n, file_name_size - n, "/%s", log_file_name);
 
 	} else {
-		if (create_log_dir(nullptr)) {
+		int n = create_log_dir(type, nullptr, file_name, file_name_size);
+		if (n < 0) {
 			return -1;
 		}
 
@@ -1415,9 +1513,9 @@ int Logger::get_log_file_name(char *file_name, size_t file_name_size)
 
 		/* look for the next file that does not exist */
 		while (file_number <= MAX_NO_LOGFILE) {
-			/* format log file path: e.g. /fs/microsd/sess001/log001.ulg */
-			snprintf(_log_file_name, sizeof(_log_file_name), "log%03u%s.ulg", file_number, replay_suffix);
-			snprintf(file_name, file_name_size, "%s/%s", _log_dir, _log_file_name);
+			/* format log file path: e.g. /fs/microsd/log/sess001/log001.ulg */
+			snprintf(log_file_name, sizeof(LogFileName::log_file_name), "log%03u%s.ulg", file_number, replay_suffix);
+			snprintf(file_name + n, file_name_size - n, "/%s", log_file_name);
 
 			if (!util::file_exist(file_name)) {
 				break;
@@ -1432,7 +1530,6 @@ int Logger::get_log_file_name(char *file_name, size_t file_name_size)
 		}
 	}
 
-
 	return 0;
 }
 
@@ -1445,55 +1542,64 @@ void Logger::setReplayFile(const char *file_name)
 	_replay_file_name = strdup(file_name);
 }
 
-void Logger::start_log_file()
+void Logger::start_log_file(LogType type)
 {
-	if (_writer.is_started(LogWriter::BackendFile) || (_writer.backend() & LogWriter::BackendFile) == 0) {
+	if (_writer.is_started(type, LogWriter::BackendFile) || (_writer.backend() & LogWriter::BackendFile) == 0) {
 		return;
 	}
 
-	PX4_INFO("Start file log");
+	PX4_INFO("Start file log (type: %s)", log_type_str(type));
 
 	char file_name[LOG_DIR_LEN] = "";
 
-	if (get_log_file_name(file_name, sizeof(file_name))) {
-		PX4_ERR("logger: failed to get log file name");
+	if (get_log_file_name(type, file_name, sizeof(file_name))) {
+		PX4_ERR("failed to get log file name");
 		return;
 	}
 
-	/* print logging path, important to find log file later */
-	mavlink_log_info(&_mavlink_log_pub, "[logger] file: %s", file_name);
+	if (type == LogType::Full) {
+		/* print logging path, important to find log file later */
+		mavlink_log_info(&_mavlink_log_pub, "[logger] file: %s", file_name);
+	}
 
-	_writer.start_log_file(file_name);
+	_writer.start_log_file(type, file_name);
 	_writer.select_write_backend(LogWriter::BackendFile);
 	_writer.set_need_reliable_transfer(true);
-	write_header();
-	write_version();
-	write_formats();
-	write_parameters();
-	write_perf_data(true);
-	write_all_add_logged_msg();
+	write_header(type);
+	write_version(type);
+	write_formats(type);
+	if (type == LogType::Full) {
+		write_parameters(type);
+		write_perf_data(true);
+	}
+	write_all_add_logged_msg(type);
 	_writer.set_need_reliable_transfer(false);
 	_writer.unselect_write_backend();
 	_writer.notify();
 
-	/* reset performance counters to get in-flight min and max values in post flight log */
-	perf_reset_all();
+	if (type == LogType::Full) {
+		/* reset performance counters to get in-flight min and max values in post flight log */
+		perf_reset_all();
 
-	_start_time_file = hrt_absolute_time();
+		initialize_load_output(PrintLoadReason::Preflight);
+	}
+
+	_statistics[(int)type].start_time_file = hrt_absolute_time();
 
-	initialize_load_output(PrintLoadReason::Preflight);
 }
 
-void Logger::stop_log_file()
+void Logger::stop_log_file(LogType type)
 {
-	if (!_writer.is_started(LogWriter::BackendFile)) {
+	if (!_writer.is_started(type, LogWriter::BackendFile)) {
 		return;
 	}
 
-	_writer.set_need_reliable_transfer(true);
-	write_perf_data(false);
-	_writer.set_need_reliable_transfer(false);
-	_writer.stop_log_file();
+	if (type == LogType::Full) {
+		_writer.set_need_reliable_transfer(true);
+		write_perf_data(false);
+		_writer.set_need_reliable_transfer(false);
+	}
+	_writer.stop_log_file(type);
 }
 
 void Logger::start_log_mavlink()
@@ -1507,12 +1613,12 @@ void Logger::start_log_mavlink()
 	_writer.start_log_mavlink();
 	_writer.select_write_backend(LogWriter::BackendMavlink);
 	_writer.set_need_reliable_transfer(true);
-	write_header();
-	write_version();
-	write_formats();
-	write_parameters();
+	write_header(LogType::Full);
+	write_version(LogType::Full);
+	write_formats(LogType::Full);
+	write_parameters(LogType::Full);
 	write_perf_data(true);
-	write_all_add_logged_msg();
+	write_all_add_logged_msg(LogType::Full);
 	_writer.set_need_reliable_transfer(false);
 	_writer.unselect_write_backend();
 	_writer.notify();
@@ -1550,7 +1656,7 @@ void Logger::perf_iterate_callback(perf_counter_t handle, void *user)
 		perf_name = "perf_counter_postflight";
 	}
 
-	callback_data->logger->write_info_multiple(perf_name, buffer, callback_data->counter != 0);
+	callback_data->logger->write_info_multiple(LogType::Full, perf_name, buffer, callback_data->counter != 0);
 	++callback_data->counter;
 }
 
@@ -1590,7 +1696,7 @@ void Logger::print_load_callback(void *user)
 			break;
 	}
 
-	callback_data->logger->write_info_multiple(perf_name, callback_data->buffer, callback_data->counter != 0);
+	callback_data->logger->write_info_multiple(LogType::Full, perf_name, callback_data->buffer, callback_data->counter != 0);
 	++callback_data->counter;
 }
 
@@ -1627,7 +1733,7 @@ void Logger::write_load_output()
 	_writer.set_need_reliable_transfer(false);
 }
 
-void Logger::write_format(const orb_metadata &meta, WrittenFormats &written_formats, ulog_message_format_s& msg, int level)
+void Logger::write_format(LogType type, const orb_metadata &meta, WrittenFormats &written_formats, ulog_message_format_s& msg, int level)
 {
 	if (level > 3) {
 		// precaution: limit recursion level. If we land here it's either a bug or nested topic definitions. In the
@@ -1641,7 +1747,7 @@ void Logger::write_format(const orb_metadata &meta, WrittenFormats &written_form
 	size_t msg_size = sizeof(msg) - sizeof(msg.format) + format_len;
 	msg.msg_size = msg_size - ULOG_MSG_HEADER_LEN;
 
-	write_message(&msg, msg_size);
+	write_message(type, &msg, msg_size);
 
 	if (!written_formats.push_back(&meta)) {
 		PX4_ERR("Array too small");
@@ -1705,7 +1811,7 @@ void Logger::write_format(const orb_metadata &meta, WrittenFormats &written_form
 					}
 				}
 				if (found_topic) {
-					write_format(*found_topic, written_formats, msg, level+1);
+					write_format(type, *found_topic, written_formats, msg, level+1);
 				}
 			} else {
 				PX4_ERR("No definition for topic %s found", fmt);
@@ -1717,7 +1823,7 @@ void Logger::write_format(const orb_metadata &meta, WrittenFormats &written_form
 	}
 }
 
-void Logger::write_formats()
+void Logger::write_formats(LogType type)
 {
 	_writer.lock();
 
@@ -1726,21 +1832,31 @@ void Logger::write_formats()
 	WrittenFormats written_formats;
 
 	// write all subscribed formats
-	for (const LoggerSubscription &sub : _subscriptions) {
-		write_format(*sub.metadata, written_formats, msg);
+	size_t sub_count = _subscriptions.size();
+	if (type == LogType::Mission) {
+		sub_count = _num_mission_subs;
+	}
+	for (size_t i = 0; i < sub_count; ++i) {
+		const LoggerSubscription &sub = _subscriptions[i];
+		write_format(type, *sub.metadata, written_formats, msg);
 	}
 
 	_writer.unlock();
 }
 
-void Logger::write_all_add_logged_msg()
+void Logger::write_all_add_logged_msg(LogType type)
 {
 	_writer.lock();
 
-	for (LoggerSubscription &sub : _subscriptions) {
+	size_t sub_count = _subscriptions.size();
+	if (type == LogType::Mission) {
+		sub_count = _num_mission_subs;
+	}
+	for (size_t i = 0; i < sub_count; ++i) {
+		LoggerSubscription &sub = _subscriptions[i];
 		for (int instance = 0; instance < ORB_MULTI_MAX_INSTANCES; ++instance) {
 			if (sub.fd[instance] >= 0) {
-				write_add_logged_msg(sub, instance);
+				write_add_logged_msg(type, sub, instance);
 			}
 		}
 	}
@@ -1748,7 +1864,7 @@ void Logger::write_all_add_logged_msg()
 	_writer.unlock();
 }
 
-void Logger::write_add_logged_msg(LoggerSubscription &subscription, int instance)
+void Logger::write_add_logged_msg(LogType type, LoggerSubscription &subscription, int instance)
 {
 	ulog_message_add_logged_s msg;
 
@@ -1773,12 +1889,11 @@ void Logger::write_add_logged_msg(LoggerSubscription &subscription, int instance
 
 	bool prev_reliable = _writer.need_reliable_transfer();
 	_writer.set_need_reliable_transfer(true);
-	write_message(&msg, msg_size);
+	write_message(type, &msg, msg_size);
 	_writer.set_need_reliable_transfer(prev_reliable);
 }
 
-/* write info message */
-void Logger::write_info(const char *name, const char *value)
+void Logger::write_info(LogType type, const char *name, const char *value)
 {
 	_writer.lock();
 	ulog_message_info_header_s msg = {};
@@ -1797,13 +1912,13 @@ void Logger::write_info(const char *name, const char *value)
 
 		msg.msg_size = msg_size - ULOG_MSG_HEADER_LEN;
 
-		write_message(buffer, msg_size);
+		write_message(type, buffer, msg_size);
 	}
 
 	_writer.unlock();
 }
 
-void Logger::write_info_multiple(const char *name, const char *value, bool is_continued)
+void Logger::write_info_multiple(LogType type, const char *name, const char *value, bool is_continued)
 {
 	_writer.lock();
 	ulog_message_info_multiple_header_s msg;
@@ -1823,25 +1938,25 @@ void Logger::write_info_multiple(const char *name, const char *value, bool is_co
 
 		msg.msg_size = msg_size - ULOG_MSG_HEADER_LEN;
 
-		write_message(buffer, msg_size);
+		write_message(type, buffer, msg_size);
 	}
 
 	_writer.unlock();
 }
 
-void Logger::write_info(const char *name, int32_t value)
+void Logger::write_info(LogType type, const char *name, int32_t value)
 {
-	write_info_template<int32_t>(name, value, "int32_t");
+	write_info_template<int32_t>(type, name, value, "int32_t");
 }
 
-void Logger::write_info(const char *name, uint32_t value)
+void Logger::write_info(LogType type, const char *name, uint32_t value)
 {
-	write_info_template<uint32_t>(name, value, "uint32_t");
+	write_info_template<uint32_t>(type, name, value, "uint32_t");
 }
 
 
 template<typename T>
-void Logger::write_info_template(const char *name, T value, const char *type_str)
+void Logger::write_info_template(LogType type, const char *name, T value, const char *type_str)
 {
 	_writer.lock();
 	ulog_message_info_header_s msg = {};
@@ -1858,12 +1973,12 @@ void Logger::write_info_template(const char *name, T value, const char *type_str
 
 	msg.msg_size = msg_size - ULOG_MSG_HEADER_LEN;
 
-	write_message(buffer, msg_size);
+	write_message(type, buffer, msg_size);
 
 	_writer.unlock();
 }
 
-void Logger::write_header()
+void Logger::write_header(LogType type)
 {
 	ulog_file_header_s header = {};
 	header.magic[0] = 'U';
@@ -1876,7 +1991,7 @@ void Logger::write_header()
 	header.magic[7] = 0x01; //file version 1
 	header.timestamp = hrt_absolute_time();
 	_writer.lock();
-	write_message(&header, sizeof(header));
+	write_message(type, &header, sizeof(header));
 
 	// write the Flags message: this MUST be written right after the ulog header
 	ulog_message_flag_bits_s flag_bits{};
@@ -1884,50 +1999,49 @@ void Logger::write_header()
 	flag_bits.msg_size = sizeof(flag_bits) - ULOG_MSG_HEADER_LEN;
 	flag_bits.msg_type = static_cast<uint8_t>(ULogMessageType::FLAG_BITS);
 
-	write_message(&flag_bits, sizeof(flag_bits));
+	write_message(type, &flag_bits, sizeof(flag_bits));
 
 	_writer.unlock();
 }
 
-/* write version info messages */
-void Logger::write_version()
+void Logger::write_version(LogType type)
 {
-	write_info("ver_sw", px4_firmware_version_string());
-	write_info("ver_sw_release", px4_firmware_version());
+	write_info(type, "ver_sw", px4_firmware_version_string());
+	write_info(type, "ver_sw_release", px4_firmware_version());
 	uint32_t vendor_version = px4_firmware_vendor_version();
 
 	if (vendor_version > 0) {
-		write_info("ver_vendor_sw_release", vendor_version);
+		write_info(type, "ver_vendor_sw_release", vendor_version);
 	}
 
-	write_info("ver_hw", px4_board_name());
+	write_info(type, "ver_hw", px4_board_name());
 	const char *board_sub_type = px4_board_sub_type();
 
 	if (board_sub_type && board_sub_type[0]) {
-		write_info("ver_hw_subtype", board_sub_type);
+		write_info(type, "ver_hw_subtype", board_sub_type);
 	}
-	write_info("sys_name", "PX4");
-	write_info("sys_os_name", px4_os_name());
+	write_info(type, "sys_name", "PX4");
+	write_info(type, "sys_os_name", px4_os_name());
 	const char *os_version = px4_os_version_string();
 
 	const char *git_branch = px4_firmware_git_branch();
 
 	if (git_branch && git_branch[0]) {
-		write_info("ver_sw_branch", git_branch);
+		write_info(type, "ver_sw_branch", git_branch);
 	}
 
 	if (os_version) {
-		write_info("sys_os_ver", os_version);
+		write_info(type, "sys_os_ver", os_version);
 	}
 
-	write_info("sys_os_ver_release", px4_os_version());
-	write_info("sys_toolchain", px4_toolchain_name());
-	write_info("sys_toolchain_ver", px4_toolchain_version());
+	write_info(type, "sys_os_ver_release", px4_os_version());
+	write_info(type, "sys_toolchain", px4_toolchain_name());
+	write_info(type, "sys_toolchain_ver", px4_toolchain_version());
 
 	const char* ecl_version = px4_ecl_lib_version_string();
 
 	if (ecl_version && ecl_version[0]) {
-		write_info("sys_lib_ecl_ver", ecl_version);
+		write_info(type, "sys_lib_ecl_ver", ecl_version);
 	}
 
 	char revision = 'U';
@@ -1936,7 +2050,7 @@ void Logger::write_version()
 	if (board_mcu_version(&revision, &chip_name, nullptr) >= 0) {
 		char mcu_ver[64];
 		snprintf(mcu_ver, sizeof(mcu_ver), "%s, rev. %c", chip_name, revision);
-		write_info("sys_mcu", mcu_ver);
+		write_info(type, "sys_mcu", mcu_ver);
 	}
 
 #ifndef BOARD_HAS_NO_UUID
@@ -1950,7 +2064,7 @@ void Logger::write_version()
 		if (write_uuid == 1) {
 			char px4_uuid_string[PX4_GUID_FORMAT_SIZE];
 			board_get_px4_guid_formated(px4_uuid_string, sizeof(px4_uuid_string));
-			write_info("sys_uuid", px4_uuid_string);
+			write_info(type, "sys_uuid", px4_uuid_string);
 		}
 	}
 #endif /* BOARD_HAS_NO_UUID */
@@ -1959,15 +2073,19 @@ void Logger::write_version()
 
 	if (_log_utc_offset != PARAM_INVALID) {
 		param_get(_log_utc_offset, &utc_offset);
-		write_info("time_ref_utc", utc_offset * 60);
+		write_info(type, "time_ref_utc", utc_offset * 60);
 	}
 
 	if (_replay_file_name) {
-		write_info("replay", _replay_file_name);
+		write_info(type, "replay", _replay_file_name);
+	}
+
+	if (type == LogType::Mission) {
+		write_info(type, "log_type", "mission");
 	}
 }
 
-void Logger::write_parameters()
+void Logger::write_parameters(LogType type)
 {
 	_writer.lock();
 	ulog_message_parameter_header_s msg = {};
@@ -1988,10 +2106,10 @@ void Logger::write_parameters()
 		if (param != PARAM_INVALID) {
 			// get parameter type and size
 			const char *type_str;
-			param_type_t type = param_type(param);
+			param_type_t ptype = param_type(param);
 			size_t value_size = 0;
 
-			switch (type) {
+			switch (ptype) {
 			case PARAM_TYPE_INT32:
 				type_str = "int32_t";
 				value_size = sizeof(int32_t);
@@ -2011,7 +2129,7 @@ void Logger::write_parameters()
 			size_t msg_size = sizeof(msg) - sizeof(msg.key) + msg.key_len;
 
 			// copy parameter value directly to buffer
-			switch (type) {
+			switch (ptype) {
 			case PARAM_TYPE_INT32:
 				param_get(param, (int32_t*)&buffer[msg_size]);
 				break;
@@ -2027,7 +2145,7 @@ void Logger::write_parameters()
 
 			msg.msg_size = msg_size - ULOG_MSG_HEADER_LEN;
 
-			write_message(buffer, msg_size);
+			write_message(type, buffer, msg_size);
 		}
 	} while ((param != PARAM_INVALID) && (param_idx < (int) param_count()));
 
@@ -2035,7 +2153,7 @@ void Logger::write_parameters()
 	_writer.notify();
 }
 
-void Logger::write_changed_parameters()
+void Logger::write_changed_parameters(LogType type)
 {
 	_writer.lock();
 	ulog_message_parameter_header_s msg = {};
@@ -2057,10 +2175,10 @@ void Logger::write_changed_parameters()
 
 			// get parameter type and size
 			const char *type_str;
-			param_type_t type = param_type(param);
+			param_type_t ptype = param_type(param);
 			size_t value_size = 0;
 
-			switch (type) {
+			switch (ptype) {
 			case PARAM_TYPE_INT32:
 				type_str = "int32_t";
 				value_size = sizeof(int32_t);
@@ -2080,7 +2198,7 @@ void Logger::write_changed_parameters()
 			size_t msg_size = sizeof(msg) - sizeof(msg.key) + msg.key_len;
 
 			// copy parameter value directly to buffer
-			switch (type) {
+			switch (ptype) {
 			case PARAM_TYPE_INT32:
 				param_get(param, (int32_t*)&buffer[msg_size]);
 				break;
@@ -2097,7 +2215,7 @@ void Logger::write_changed_parameters()
 			// msg_size is now 1 (msg_type) + 2 (msg_size) + 1 (key_len) + key_len + value_size
 			msg.msg_size = msg_size - ULOG_MSG_HEADER_LEN;
 
-			write_message(buffer, msg_size);
+			write_message(type, buffer, msg_size);
 		}
 	} while ((param != PARAM_INVALID) && (param_idx < (int) param_count()));
 
diff --git a/src/modules/logger/logger.h b/src/modules/logger/logger.h
index f0bae107d258b7a7d678843cb5c9c64d09769859..d14633d3eeadf5cac232dea507536b173336b945 100644
--- a/src/modules/logger/logger.h
+++ b/src/modules/logger/logger.h
@@ -64,7 +64,13 @@ enum class SDLogProfileMask : int32_t {
 	SYSTEM_IDENTIFICATION = 1 << 3,
 	HIGH_RATE =             1 << 4,
 	DEBUG_TOPICS =          1 << 5,
-	SENSOR_COMPARISON =	1 << 6
+	SENSOR_COMPARISON =     1 << 6
+};
+
+enum class MissionLogType : int32_t {
+	Disabled =               0,
+	Complete =               1,
+	Geotagging =             2
 };
 
 inline bool operator&(SDLogProfileMask a, SDLogProfileMask b)
@@ -151,7 +157,7 @@ public:
 	 */
 	static bool request_stop_static();
 
-	void print_statistics();
+	void print_statistics(LogType type);
 
 	void set_arm_override(bool override) { _arm_override = override; }
 
@@ -164,35 +170,62 @@ private:
 	};
 
 	static constexpr size_t 	MAX_TOPICS_NUM = 64; /**< Maximum number of logged topics */
+	static constexpr int		MAX_MISSION_TOPICS_NUM = 5; /**< Maximum number of mission topics */
 	static constexpr unsigned	MAX_NO_LOGFILE = 999;	/**< Maximum number of log files */
-	static constexpr const char	*LOG_ROOT = PX4_STORAGEDIR "/log";
+	static constexpr const char	*LOG_ROOT[(int)LogType::Count] = {
+		PX4_STORAGEDIR "/log",
+		PX4_STORAGEDIR "/mission_log"
+	};
+
+	struct LogFileName {
+		char log_dir[12];           ///< e.g. "2018-01-01" or "sess001"
+		int sess_dir_index{1};      ///< search starting index for 'sess<i>' directory name
+		char log_file_name[31];     ///< e.g. "log001.ulg" or "12_09_00_replayed.ulg"
+		bool has_log_dir{false};
+	};
+
+	struct Statistics {
+		hrt_abstime start_time_file{0};				///< Time when logging started, file backend (not the logger thread)
+		hrt_abstime dropout_start{0};				///< start of current dropout (0 = no dropout)
+		float max_dropout_duration{0.0f};			///< max duration of dropout [s]
+		size_t write_dropouts{0};				///< failed buffer writes due to buffer overflow
+		size_t high_water{0};					///< maximum used write buffer
+	};
+
+	struct MissionSubscription {
+		unsigned min_delta_ms;        ///< minimum time between 2 topic writes [ms]
+		unsigned next_write_time;     ///< next time to write in 0.1 seconds
+	};
 
 	/**
 	 * Write an ADD_LOGGED_MSG to the log for a all current subscriptions and instances
 	 */
-	void write_all_add_logged_msg();
+	void write_all_add_logged_msg(LogType type);
 
 	/**
 	 * Write an ADD_LOGGED_MSG to the log for a given subscription and instance.
 	 * _writer.lock() must be held when calling this.
 	 */
-	void write_add_logged_msg(LoggerSubscription &subscription, int instance);
+	void write_add_logged_msg(LogType type, LoggerSubscription &subscription, int instance);
 
 	/**
 	 * Create logging directory
+	 * @param type
 	 * @param tt if not null, use it for the directory name
-	 * @return 0 on success
+	 * @param log_dir returned log directory path
+	 * @param log_dir_len log_dir buffer length
+	 * @return string length of log_dir (excluding terminating null-char), <0 on error
 	 */
-	int create_log_dir(tm *tt);
+	int create_log_dir(LogType type, tm *tt, char *log_dir, int log_dir_len);
 
 	/**
 	 * Get log file name with directory (create it if necessary)
 	 */
-	int get_log_file_name(char *file_name, size_t file_name_size);
+	int get_log_file_name(LogType type, char *file_name, size_t file_name_size);
 
-	void start_log_file();
+	void start_log_file(LogType type);
 
-	void stop_log_file();
+	void stop_log_file(LogType type);
 
 	void start_log_mavlink();
 
@@ -201,7 +234,8 @@ private:
 	/** check if mavlink logging can be started */
 	bool can_start_mavlink_log() const
 	{
-		return !_writer.is_started(LogWriter::BackendMavlink) && (_writer.backend() & LogWriter::BackendMavlink) != 0;
+		return !_writer.is_started(LogType::Full, LogWriter::BackendMavlink)
+		       && (_writer.backend() & LogWriter::BackendMavlink) != 0;
 	}
 
 	/** get the configured backend as string */
@@ -210,13 +244,14 @@ private:
 	/**
 	 * write the file header with file magic and timestamp.
 	 */
-	void write_header();
+	void write_header(LogType type);
 
 	/// Array to store written formats (add some more for nested definitions)
 	using WrittenFormats = Array < const orb_metadata *, MAX_TOPICS_NUM + 10 >;
 
-	void write_format(const orb_metadata &meta, WrittenFormats &written_formats, ulog_message_format_s &msg, int level = 1);
-	void write_formats();
+	void write_format(LogType type, const orb_metadata &meta, WrittenFormats &written_formats, ulog_message_format_s &msg,
+			  int level = 1);
+	void write_formats(LogType type);
 
 	/**
 	 * write performance counters
@@ -234,22 +269,22 @@ private:
 	 */
 	static void print_load_callback(void *user);
 
-	void write_version();
+	void write_version(LogType type);
 
-	void write_info(const char *name, const char *value);
-	void write_info_multiple(const char *name, const char *value, bool is_continued);
-	void write_info(const char *name, int32_t value);
-	void write_info(const char *name, uint32_t value);
+	void write_info(LogType type, const char *name, const char *value);
+	void write_info_multiple(LogType type, const char *name, const char *value, bool is_continued);
+	void write_info(LogType type, const char *name, int32_t value);
+	void write_info(LogType type, const char *name, uint32_t value);
 
 	/** generic common template method for write_info variants */
 	template<typename T>
-	void write_info_template(const char *name, T value, const char *type_str);
+	void write_info_template(LogType type, const char *name, T value, const char *type_str);
 
-	void write_parameters();
+	void write_parameters(LogType type);
 
-	void write_changed_parameters();
+	void write_changed_parameters(LogType type);
 
-	inline bool copy_if_updated_multi(LoggerSubscription &sub, int multi_instance, void *buffer, bool try_to_subscribe);
+	inline bool copy_if_updated_multi(int sub_idx, int multi_instance, void *buffer, bool try_to_subscribe);
 
 	/**
 	 * Check if a topic instance exists and subscribe to it
@@ -262,7 +297,7 @@ private:
 	 * Must be called with _writer.lock() held.
 	 * @return true if data written, false otherwise (on overflow)
 	 */
-	bool write_message(void *ptr, size_t size);
+	bool write_message(LogType type, void *ptr, size_t size);
 
 	/**
 	 * Parse a file containing a list of uORB topics to log, calling add_topic for each
@@ -271,6 +306,20 @@ private:
 	 */
 	int add_topics_from_file(const char *fname);
 
+	/**
+	 * Add topic subscriptions based on the configured mission log type
+	 */
+	void initialize_mission_topics(MissionLogType type);
+
+	/**
+	 * Add a topic to be logged for the mission log (it's also added to the full log).
+	 * The interval is expected to be 0 or large (in the order of 0.1 seconds or higher).
+	 * Must be called before all other topics are added.
+	 * @param name topic name
+	 * @param interval limit rate if >0 [ms], otherwise log as fast as the topic is updated.
+	 */
+	void add_mission_topic(const char *name, unsigned interval = 0);
+
 	/**
 	 * Add topic subscriptions based on the _sdlog_profile_handle parameter
 	 */
@@ -287,9 +336,10 @@ private:
 	/**
 	 * check current arming state and start/stop logging if state changed and according to configured params.
 	 * @param vehicle_status_sub
+	 * @param mission_log_type
 	 * @return true if log started
 	 */
-	bool check_arming_state(int vehicle_status_sub);
+	bool check_arming_state(int vehicle_status_sub, MissionLogType mission_log_type);
 
 	void handle_vehicle_command_update(int vehicle_command_sub, orb_advert_t &vehicle_command_ack_pub);
 	void ack_vehicle_command(orb_advert_t &vehicle_command_ack_pub, vehicle_command_s *cmd, uint32_t result);
@@ -307,25 +357,22 @@ private:
 
 	uint8_t						*_msg_buffer{nullptr};
 	int						_msg_buffer_len{0};
-	char 						_log_dir[LOG_DIR_LEN] {};
-	int						_sess_dir_index{1}; ///< search starting index for 'sess<i>' directory name
-	char 						_log_file_name[32];
-	bool						_has_log_dir{false};
+
+	LogFileName					_file_name[(int)LogType::Count];
+
 	bool						_was_armed{false};
 	bool						_arm_override{false};
 
-
-	// statistics
-	hrt_abstime					_start_time_file{0}; ///< Time when logging started, file backend (not the logger thread)
-	hrt_abstime					_dropout_start{0}; ///< start of current dropout (0 = no dropout)
-	float						_max_dropout_duration{0.0f}; ///< max duration of dropout [s]
-	size_t						_write_dropouts{0}; ///< failed buffer writes due to buffer overflow
-	size_t						_high_water{0}; ///< maximum used write buffer
+	Statistics					_statistics[(int)LogType::Count];
 
 	const bool 					_log_on_start;
 	const bool 					_log_until_shutdown;
 	const bool					_log_name_timestamp;
-	Array<LoggerSubscription, MAX_TOPICS_NUM>	_subscriptions;
+
+	Array<LoggerSubscription, MAX_TOPICS_NUM>	_subscriptions; ///< all subscriptions for full & mission log (in front)
+	MissionSubscription 				_mission_subscriptions[MAX_MISSION_TOPICS_NUM]; ///< additional data for mission subscriptions
+	int						_num_mission_subs{0};
+
 	LogWriter					_writer;
 	uint32_t					_log_interval{0};
 	const orb_metadata				*_polling_topic_meta{nullptr}; ///< if non-null, poll on this topic instead of sleeping
@@ -333,15 +380,15 @@ private:
 	uint8_t						_next_topic_id{0}; ///< id of next subscribed ulog topic
 	char						*_replay_file_name{nullptr};
 	bool						_should_stop_file_log{false}; /**< if true _next_load_print is set and file logging
-											will be stopped after load printing */
+											will be stopped after load printing (for the full log) */
 	print_load_s					_load{}; ///< process load data
 	hrt_abstime					_next_load_print{0}; ///< timestamp when to print the process load
 	PrintLoadReason					_print_load_reason;
 
-	// control
 	param_t						_sdlog_profile_handle{PARAM_INVALID};
 	param_t						_log_utc_offset{PARAM_INVALID};
 	param_t						_log_dirs_max{PARAM_INVALID};
+	param_t						_mission_log{PARAM_INVALID};
 };
 
 } //namespace logger
diff --git a/src/modules/logger/params.c b/src/modules/logger/params.c
index a2272d54fcb3fbdf57ecae9aaee6b5a1b628c55e..857614056b6f4c559d90c2a4ace275de4f9fea2b 100644
--- a/src/modules/logger/params.c
+++ b/src/modules/logger/params.c
@@ -59,13 +59,35 @@ PARAM_DEFINE_INT32(SDLOG_UTC_OFFSET, 0);
  * @value 1 from boot until disarm
  * @value 2 from boot until shutdown
  *
- * @min 0
- * @max 2
  * @reboot_required true
  * @group SD Logging
  */
 PARAM_DEFINE_INT32(SDLOG_MODE, 0);
 
+/**
+ * Mission Log
+ *
+ * If enabled, a second mission log file will be written to the SD card.
+ * This is a small log file with reduced information content (such as the
+ * vehicle position) that for example can be used for flight statistics,
+ * regulatory purposes or geotagging.
+ *
+ * The normal full log file will still be generated and it contains all
+ * the data that a mission log contains.
+ *
+ * The different modes can be used to further reduce the amount of logged data
+ * and thus the log file size. Geotagging for instance will only log data
+ * required for geotagging.
+ *
+ * @value 0 Disabled
+ * @value 1 Complete
+ * @value 2 Geotagging
+ *
+ * @reboot_required true
+ * @group SD Logging
+ */
+PARAM_DEFINE_INT32(SDLOG_MISSION, 0);
+
 /**
  * Logging topic profile (integer bitmask).
  *
@@ -111,6 +133,8 @@ PARAM_DEFINE_INT32(SDLOG_PROFILE, 3);
  * If this is set to 0, old directories will only be removed if the free space falls below
  * the minimum.
  *
+ * Note: this does not apply to mission log files.
+ *
  * @min 0
  * @max 1000
  * @reboot_required true