//------------------------------------------------------------------- void LogListHelper::delete_all(const char* dir) { //-- Open log directory DIR* dp = opendir(dir); if (dp == nullptr) { return; } struct dirent entry, *result = nullptr; while (readdir_r(dp, &entry, &result) == 0) { // no more entries? if (result == nullptr) { break; } if (entry.d_type == PX4LOG_DIRECTORY && entry.d_name[0] != '.') { char log_path[128]; snprintf(log_path, sizeof(log_path), "%s/%s", dir, entry.d_name); LogListHelper::delete_all(log_path); if(rmdir(log_path)) { PX4LOG_WARN("MavlinkLogHandler::delete_all Error removing %s\n", log_path); } } if (entry.d_type == PX4LOG_REGULAR_FILE) { char log_path[128]; snprintf(log_path, sizeof(log_path), "%s/%s", dir, entry.d_name); if(unlink(log_path)) { PX4LOG_WARN("MavlinkLogHandler::delete_all Error deleting %s\n", log_path); } } } closedir(dp); }
//------------------------------------------------------------------- void LogListHelper::_init() { /* When this helper is created, it scans the log directory and collects all log files found into one file for easy, subsequent access. */ current_log_filename[0] = 0; // Remove old log data file (if any) unlink(kLogData); // Open log directory DIR *dp = opendir(kLogRoot); if (dp == nullptr) { // No log directory. Nothing to do. return; } // Create work file FILE *f = ::fopen(kTmpData, "w"); if (!f) { PX4LOG_WARN("MavlinkLogHandler::init Error creating %s\n", kTmpData); closedir(dp); return; } // Scan directory and collect log files struct dirent *result = nullptr; while ((result = readdir(dp))) { if (result->d_type == PX4LOG_DIRECTORY) { time_t tt = 0; char log_path[128]; snprintf(log_path, sizeof(log_path), "%s/%s", kLogRoot, result->d_name); if (_get_session_date(log_path, result->d_name, tt)) { _scan_logs(f, log_path, tt); } } } closedir(dp); fclose(f); // Rename temp file to data file if (rename(kTmpData, kLogData)) { PX4LOG_WARN("MavlinkLogHandler::init Error renaming %s\n", kTmpData); log_count = 0; } }
//------------------------------------------------------------------- void MavlinkLogHandler::_log_request_data(const mavlink_message_t *msg) { //-- If we haven't listed, we can't do much if (!_pLogHandlerHelper) { PX4LOG_WARN("MavlinkLogHandler::_log_request_data Log request with no list requested.\n"); return; } mavlink_log_request_data_t request; mavlink_msg_log_request_data_decode(msg, &request); //-- Does the requested log exist? if (request.id >= _pLogHandlerHelper->log_count) { PX4LOG_WARN("MavlinkLogHandler::_log_request_data Requested log %u but we only have %u.\n", request.id, _pLogHandlerHelper->log_count); return; } //-- If we were sending log entries, stop it _pLogHandlerHelper->current_status = LogListHelper::LOG_HANDLER_IDLE; if (_pLogHandlerHelper->current_log_index != request.id) { //-- Init send log dataset _pLogHandlerHelper->current_log_filename[0] = 0; _pLogHandlerHelper->current_log_index = request.id; uint32_t time_utc = 0; _pLogHandlerHelper->get_entry(_pLogHandlerHelper->current_log_index, _pLogHandlerHelper->current_log_size, time_utc, _pLogHandlerHelper->current_log_filename); _pLogHandlerHelper->open_for_transmit(); } _pLogHandlerHelper->current_log_data_offset = request.ofs; if (_pLogHandlerHelper->current_log_data_offset >= _pLogHandlerHelper->current_log_size) { _pLogHandlerHelper->current_log_data_remaining = 0; } else { _pLogHandlerHelper->current_log_data_remaining = _pLogHandlerHelper->current_log_size - request.ofs; } if (_pLogHandlerHelper->current_log_data_remaining > request.count) { _pLogHandlerHelper->current_log_data_remaining = request.count; } //-- Enable streaming _pLogHandlerHelper->current_status = LogListHelper::LOG_HANDLER_SENDING_DATA; }
//------------------------------------------------------------------- size_t MavlinkLogHandler::_log_send_listing() { mavlink_log_entry_t response; uint32_t size, date; _pLogHandlerHelper->get_entry(_pLogHandlerHelper->next_entry, size, date); response.size = size; response.time_utc = date; response.id = _pLogHandlerHelper->next_entry; response.num_logs = _pLogHandlerHelper->log_count; response.last_log_num = _pLogHandlerHelper->last_entry; mavlink_msg_log_entry_send_struct(_mavlink->get_channel(), &response); //-- If we're done listing, flag it. if (_pLogHandlerHelper->next_entry == _pLogHandlerHelper->last_entry) { _pLogHandlerHelper->current_status = LogListHelper::LOG_HANDLER_IDLE; } else { _pLogHandlerHelper->next_entry++; } PX4LOG_WARN("MavlinkLogHandler::_log_send_listing id: %u count: %u last: %u size: %u date: %u status: %d\n", response.id, response.num_logs, response.last_log_num, response.size, response.time_utc, _pLogHandlerHelper->current_status); return sizeof(response); }
//------------------------------------------------------------------- void MavlinkLogHandler::_log_request_erase(const mavlink_message_t* /*msg*/) { /* mavlink_log_erase_t request; mavlink_msg_log_erase_decode(msg, &request); */ if (_pLogHandlerHelper) { delete _pLogHandlerHelper; _pLogHandlerHelper = 0; } //-- Delete all logs LogListHelper::delete_all(kLogRoot); //-- Now delete all "msgs_*" from root DIR* dp = opendir(kSDRoot); if (dp) { struct dirent entry, *result = nullptr; while (readdir_r(dp, &entry, &result) == 0) { // no more entries? if (!result) { break; } if (entry.d_type == PX4LOG_REGULAR_FILE) { if(!memcmp(entry.d_name, "msgs_", 5)) { char msg_path[128]; snprintf(msg_path, sizeof(msg_path), "%s%s", kSDRoot, entry.d_name); if(unlink(msg_path)) { PX4LOG_WARN("MavlinkLogHandler::_log_request_erase Error deleting %s\n", msg_path); } } } } closedir(dp); } }
//------------------------------------------------------------------- void MavlinkLogHandler::_log_request_list(const mavlink_message_t *msg) { mavlink_log_request_list_t request; mavlink_msg_log_request_list_decode(msg, &request); //-- Check for re-requests (data loss) or new request if(_pLogHandlerHelper) { _pLogHandlerHelper->current_status = LogListHelper::LOG_HANDLER_IDLE; //-- Is this a new request? if((request.end - request.start) > _pLogHandlerHelper->log_count) { delete _pLogHandlerHelper; _pLogHandlerHelper = NULL; } } if(!_pLogHandlerHelper) { //-- Prepare new request _pLogHandlerHelper = new LogListHelper; } if (_pLogHandlerHelper->log_count) { //-- Define (and clamp) range _pLogHandlerHelper->next_entry = request.start < _pLogHandlerHelper->log_count ? request.start : _pLogHandlerHelper->log_count - 1; _pLogHandlerHelper->last_entry = request.end < _pLogHandlerHelper->log_count ? request.end : _pLogHandlerHelper->log_count - 1; } PX4LOG_WARN("\nMavlinkLogHandler::_log_request_list: start: %u last: %u count: %u\n", _pLogHandlerHelper->next_entry, _pLogHandlerHelper->last_entry, _pLogHandlerHelper->log_count); //-- Enable streaming _pLogHandlerHelper->current_status = LogListHelper::LOG_HANDLER_LISTING; }
//------------------------------------------------------------------- size_t LogListHelper::get_log_data(uint8_t len, uint8_t* buffer) { if(!current_log_filename[0]) return 0; if (!current_log_filep) { PX4LOG_WARN("MavlinkLogHandler::get_log_data file not open %s\n", current_log_filename); return 0; } long int offset = current_log_data_offset - ftell(current_log_filep); if(offset && fseek(current_log_filep, offset, SEEK_CUR)) { fclose(current_log_filep); PX4LOG_WARN("MavlinkLogHandler::get_log_data Seek error in %s\n", current_log_filename); return 0; } size_t result = fread(buffer, 1, len, current_log_filep); return result; }
//------------------------------------------------------------------- void MavlinkLogHandler::_log_request_end(const mavlink_message_t* /*msg*/) { PX4LOG_WARN("MavlinkLogHandler::_log_request_end\n"); if (_pLogHandlerHelper) { delete _pLogHandlerHelper; _pLogHandlerHelper = 0; } }
//------------------------------------------------------------------- bool LogListHelper::open_for_transmit() { if (current_log_filep) { ::fclose(current_log_filep); current_log_filep = 0; } current_log_filep = ::fopen(current_log_filename, "rb"); if (!current_log_filep) { PX4LOG_WARN("MavlinkLogHandler::open_for_transmit Could not open %s\n", current_log_filename); return false; } return true; }