【NextPilot日志移植】日志写入流程
📝 文件后端日志写入流程详解
当后端选择文件时,日志写入过程主要涉及 LogWriter 和 LogWriterFile 类的协作。以下是详细的日志写入过程解释及涉及的代码:
1. LogWriter 类初始化
在 LogWriter 类的构造函数中,如果配置的后端包含 BackendFile,则会创建一个 LogWriterFile 对象。
LogWriter::LogWriter(Backend configured_backend, size_t file_buffer_size) :_backend(configured_backend) {if (configured_backend & BackendFile) {_log_writer_file_for_write = _log_writer_file = new LogWriterFile(file_buffer_size);if (!_log_writer_file) {PX4_ERR("LogWriterFile allocation failed");}}// ... 其他代码
}
2. 启动文件日志
在 Logger 类中,调用 start_log_file 方法启动文件日志。该方法会获取日志文件名,设置加密参数,调用 LogWriter 的 start_log_file 方法启动日志,并写入日志头、版本信息、格式信息等。
void Logger::start_log_file(LogType type) {if (_writer.is_started(type, LogWriter::BackendFile) || (_writer.backend() & LogWriter::BackendFile) == 0) {return;}// ... 其他代码char file_name[LOG_DIR_LEN] = "";if (get_log_file_name(type, file_name, sizeof(file_name), type == LogType::Full)) {PX4_ERR("failed to get log file name");return;}#if defined(PX4_CRYPTO)_writer.set_encryption_parameters((px4_crypto_algorithm_t)_param_sdlog_crypto_algorithm.get(),_param_sdlog_crypto_key.get(), _param_sdlog_crypto_exchange_key.get());
#endif_writer.start_log_file(type, file_name);_writer.select_write_backend(LogWriter::BackendFile);_writer.set_need_reliable_transfer(true);write_header(type);write_version(type);write_formats(type);// ... 其他代码_writer.set_need_reliable_transfer(false);_writer.unselect_write_backend();_writer.notify();// ... 其他代码
}
3. LogWriter 调用 LogWriterFile 启动日志
LogWriter 的 start_log_file 方法会调用 LogWriterFile 的 start_log 方法。
void LogWriter::start_log_file(LogType type, const char *filename) {if (_log_writer_file) {_log_writer_file->start_log(type, filename);}
}
4. LogWriterFile 启动日志
LogWriterFile 的 start_log 方法会打开文件并设置 _should_run 标志。
bool LogWriterFile::LogFileBuffer::start_log(const char *filename) {_fd = open(filename, O_CREAT | O_TRUNC | O_WRONLY, 0666);if (_fd < 0) {PX4_ERR("failed to open log file (%s)", filename);return false;}_should_run = true;return true;
}
5. 写入日志消息
在 Logger 类中,调用 write_message 方法写入日志消息。该方法会调用 LogWriter 的 write_message 方法。
bool Logger::write_message(LogType type, void *ptr, size_t size) {_writer.lock();bool ret = _writer.write_message(type, ptr, size) == 0;_writer.unlock();return ret;
}
6. LogWriter 调用 LogWriterFile 写入消息
LogWriter 的 write_message 方法会调用 LogWriterFile 的 write_message 方法。
int LogWriter::write_message(LogType type, void *ptr, size_t size, uint64_t dropout_start) {int ret_file = 0;if (_log_writer_file_for_write) {ret_file = _log_writer_file_for_write->write_message(type, ptr, size, dropout_start);}// ... 其他代码return ret_file;
}
7. LogWriterFile 写入消息
LogWriterFile 的 write_message 方法会将消息写入缓冲区。
int LogWriterFile::write_message(LogType type, void *ptr, size_t size, uint64_t dropout_start) {LogFileBuffer &buffer = _buffers[(int)type];if (buffer.available() < size) {return -1; // 缓冲区空间不足}buffer.write_no_check(ptr, size);notify(); // 通知写入线程有新数据return 0;
}
8. LogWriterFile 写入线程处理
LogWriterFile 的 run 方法是一个循环,会不断检查缓冲区是否有数据,并将数据写入文件。
void LogWriterFile::run() {while (!_exit_thread.load()) {// ... 其他代码while (true) {const hrt_abstime now = hrt_absolute_time();// ... 其他代码int i = (int)LogType::Count - 1;while (i >= 0) {void *read_ptr;bool is_part;LogFileBuffer &buffer = _buffers[i];size_t available = buffer.get_read_ptr(&read_ptr, &is_part);// ... 其他代码if (available >= min_available[i] || is_part || (!buffer._should_run && available > 0)) {pthread_mutex_unlock(&_mtx);// ... 其他代码int written = buffer.write_to_file(read_ptr, available, call_fsync);// ... 其他代码if (written >= 0) {pthread_mutex_lock(&_mtx);buffer.mark_read(written);// ... 其他代码} else {// ... 其他代码}}// ... 其他代码}// ... 其他代码}// ... 其他代码}
}
9. LogWriterFile 写入文件
LogWriterFile 的 LogFileBuffer 类的 write_to_file 方法会将数据写入文件。
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;
}
总结
整个文件日志写入过程可以概括为:
LogWriter初始化时创建LogWriterFile对象。Logger调用start_log_file方法启动文件日志。LogWriter调用LogWriterFile的start_log方法打开文件。Logger调用write_message方法写入日志消息。LogWriter调用LogWriterFile的write_message方法将消息写入缓冲区。LogWriterFile的写入线程不断检查缓冲区,将数据写入文件。
通过以上步骤,实现了文件后端的日志写入功能。
