AP_Logger: convert to use AP_Filesystem

This commit is contained in:
Andrew Tridgell 2019-08-01 15:14:22 +10:00
parent fb50ec2a1d
commit 667b4e045a
3 changed files with 46 additions and 100 deletions

View File

@ -112,8 +112,7 @@ void AP_Logger::Init(const struct LogStructure *structures, uint8_t num_types)
_num_types = num_types; _num_types = num_types;
_structures = structures; _structures = structures;
#if defined(HAL_BOARD_LOG_DIRECTORY) #if defined(HAL_BOARD_LOG_DIRECTORY) && HAVE_FILESYSTEM_SUPPORT
#if HAL_OS_POSIX_IO || HAL_OS_FATFS_IO
if (_params.backend_types & uint8_t(Backend_Type::FILESYSTEM)) { if (_params.backend_types & uint8_t(Backend_Type::FILESYSTEM)) {
LoggerMessageWriter_DFLogStart *message_writer = LoggerMessageWriter_DFLogStart *message_writer =
new LoggerMessageWriter_DFLogStart(); new LoggerMessageWriter_DFLogStart();
@ -128,8 +127,7 @@ void AP_Logger::Init(const struct LogStructure *structures, uint8_t num_types)
_next_backend++; _next_backend++;
} }
} }
#endif #endif // HAVE_FILESYSTEM_SUPPORT
#endif // HAL_BOARD_LOG_DIRECTORY
#if LOGGER_MAVLINK_SUPPORT #if LOGGER_MAVLINK_SUPPORT
if (_params.backend_types & uint8_t(Backend_Type::MAVLINK)) { if (_params.backend_types & uint8_t(Backend_Type::MAVLINK)) {

View File

@ -11,39 +11,18 @@
*/ */
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Filesystem/AP_Filesystem.h>
#if HAL_OS_POSIX_IO || HAL_OS_FATFS_IO #if HAVE_FILESYSTEM_SUPPORT
#include "AP_Logger_File.h" #include "AP_Logger_File.h"
#include <AP_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_InternalError/AP_InternalError.h> #include <AP_InternalError/AP_InternalError.h>
#include <AP_RTC/AP_RTC.h> #include <AP_RTC/AP_RTC.h>
#if HAL_OS_POSIX_IO
#include <unistd.h>
#include <errno.h>
#include <stdlib.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <assert.h>
#include <stdio.h>
#include <time.h>
#include <dirent.h>
#if defined(__APPLE__) && defined(__MACH__)
#include <sys/param.h>
#include <sys/mount.h>
#else
#include <sys/statfs.h>
#endif
#endif
#if HAL_OS_FATFS_IO
#include <stdio.h>
#endif
#include <AP_Math/AP_Math.h> #include <AP_Math/AP_Math.h>
#include <GCS_MAVLink/GCS.h> #include <GCS_MAVLink/GCS.h>
#include <stdio.h>
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
@ -89,9 +68,9 @@ void AP_Logger_File::Init()
} }
EXPECT_DELAY_MS(3000); EXPECT_DELAY_MS(3000);
ret = stat(_log_directory, &st); ret = AP::FS().stat(_log_directory, &st);
if (ret == -1) { if (ret == -1) {
ret = mkdir(_log_directory, 0777); ret = AP::FS().mkdir(_log_directory);
} }
if (ret == -1 && errno != EEXIST) { if (ret == -1 && errno != EEXIST) {
printf("Failed to create log directory %s : %s\n", _log_directory, strerror(errno)); printf("Failed to create log directory %s : %s\n", _log_directory, strerror(errno));
@ -125,7 +104,7 @@ bool AP_Logger_File::file_exists(const char *filename) const
{ {
struct stat st; struct stat st;
EXPECT_DELAY_MS(3000); EXPECT_DELAY_MS(3000);
if (stat(filename, &st) == -1) { if (AP::FS().stat(filename, &st) == -1) {
// hopefully errno==ENOENT. If some error occurs it is // hopefully errno==ENOENT. If some error occurs it is
// probably better to assume this file exists. // probably better to assume this file exists.
return false; return false;
@ -190,18 +169,7 @@ bool AP_Logger_File::CardInserted(void) const
// returns -1 on error // returns -1 on error
int64_t AP_Logger_File::disk_space_avail() int64_t AP_Logger_File::disk_space_avail()
{ {
#if HAL_OS_POSIX_IO return AP::FS().disk_free(_log_directory);
struct statfs _stats;
if (statfs(_log_directory, &_stats) < 0) {
return -1;
}
return (((int64_t)_stats.f_bavail) * _stats.f_bsize);
#elif HAL_OS_FATFS_IO
return fs_getfree();
#else
// return a fake disk space size
return 100*1000*1000UL;
#endif
} }
// returns the total amount of disk space (in use + available) in // returns the total amount of disk space (in use + available) in
@ -209,18 +177,7 @@ int64_t AP_Logger_File::disk_space_avail()
// returns -1 on error // returns -1 on error
int64_t AP_Logger_File::disk_space() int64_t AP_Logger_File::disk_space()
{ {
#if HAL_OS_POSIX_IO return AP::FS().disk_space(_log_directory);
struct statfs _stats;
if (statfs(_log_directory, &_stats) < 0) {
return -1;
}
return (((int64_t)_stats.f_blocks) * _stats.f_bsize);
#elif HAL_OS_FATFS_IO
return fs_gettotal();
#else
// return fake disk space size
return 200*1000*1000UL;
#endif
} }
// returns the available space in _log_directory as a percentage // returns the available space in _log_directory as a percentage
@ -258,7 +215,7 @@ uint16_t AP_Logger_File::find_oldest_log()
// relying on the min_avail_space_percent feature we could end up // relying on the min_avail_space_percent feature we could end up
// doing a *lot* of asprintf()s and stat()s // doing a *lot* of asprintf()s and stat()s
EXPECT_DELAY_MS(3000); EXPECT_DELAY_MS(3000);
DIR *d = opendir(_log_directory); DIR *d = AP::FS().opendir(_log_directory);
if (d == nullptr) { if (d == nullptr) {
// SD card may have died? On linux someone may have rm-rf-d // SD card may have died? On linux someone may have rm-rf-d
return 0; return 0;
@ -266,7 +223,7 @@ uint16_t AP_Logger_File::find_oldest_log()
// we only remove files which look like xxx.BIN // we only remove files which look like xxx.BIN
EXPECT_DELAY_MS(3000); EXPECT_DELAY_MS(3000);
for (struct dirent *de=readdir(d); de; de=readdir(d)) { for (struct dirent *de=AP::FS().readdir(d); de; de=AP::FS().readdir(d)) {
EXPECT_DELAY_MS(3000); EXPECT_DELAY_MS(3000);
uint8_t length = strlen(de->d_name); uint8_t length = strlen(de->d_name);
if (length < 5) { if (length < 5) {
@ -301,7 +258,7 @@ uint16_t AP_Logger_File::find_oldest_log()
} }
} }
} }
closedir(d); AP::FS().closedir(d);
_cached_oldest_log = current_oldest_log; _cached_oldest_log = current_oldest_log;
return current_oldest_log; return current_oldest_log;
@ -346,7 +303,7 @@ void AP_Logger_File::Prep_MinSpace()
hal.console->printf("Removing (%s) for minimum-space requirements (%.2f%% < %.0f%%)\n", hal.console->printf("Removing (%s) for minimum-space requirements (%.2f%% < %.0f%%)\n",
filename_to_remove, (double)avail, (double)min_avail_space_percent); filename_to_remove, (double)avail, (double)min_avail_space_percent);
EXPECT_DELAY_MS(2000); EXPECT_DELAY_MS(2000);
if (unlink(filename_to_remove) == -1) { if (AP::FS().unlink(filename_to_remove) == -1) {
hal.console->printf("Failed to remove %s: %s\n", filename_to_remove, strerror(errno)); hal.console->printf("Failed to remove %s: %s\n", filename_to_remove, strerror(errno));
free(filename_to_remove); free(filename_to_remove);
if (errno == ENOENT) { if (errno == ENOENT) {
@ -473,12 +430,12 @@ void AP_Logger_File::EraseAll()
break; break;
} }
EXPECT_DELAY_MS(3000); EXPECT_DELAY_MS(3000);
unlink(fname); AP::FS().unlink(fname);
free(fname); free(fname);
} }
char *fname = _lastlog_file_name(); char *fname = _lastlog_file_name();
if (fname != nullptr) { if (fname != nullptr) {
unlink(fname); AP::FS().unlink(fname);
free(fname); free(fname);
} }
@ -572,19 +529,15 @@ uint16_t AP_Logger_File::find_last_log()
return ret; return ret;
} }
EXPECT_DELAY_MS(3000); EXPECT_DELAY_MS(3000);
int fd = open(fname, O_RDONLY|O_CLOEXEC); int fd = AP::FS().open(fname, O_RDONLY);
free(fname); free(fname);
if (fd != -1) { if (fd != -1) {
char buf[10]; char buf[10];
memset(buf, 0, sizeof(buf)); memset(buf, 0, sizeof(buf));
if (read(fd, buf, sizeof(buf)-1) > 0) { if (AP::FS().read(fd, buf, sizeof(buf)-1) > 0) {
#if HAL_OS_POSIX_IO
sscanf(buf, "%u", &ret);
#else
ret = strtol(buf, NULL, 10); ret = strtol(buf, NULL, 10);
#endif
} }
close(fd); AP::FS().close(fd);
} }
return ret; return ret;
} }
@ -606,7 +559,7 @@ uint32_t AP_Logger_File::_get_log_size(const uint16_t log_num)
} }
struct stat st; struct stat st;
EXPECT_DELAY_MS(3000); EXPECT_DELAY_MS(3000);
if (::stat(fname, &st) != 0) { if (AP::FS().stat(fname, &st) != 0) {
printf("Unable to fetch Log File Size: %s\n", strerror(errno)); printf("Unable to fetch Log File Size: %s\n", strerror(errno));
free(fname); free(fname);
return 0; return 0;
@ -636,7 +589,7 @@ uint32_t AP_Logger_File::_get_log_time(const uint16_t log_num)
} }
struct stat st; struct stat st;
EXPECT_DELAY_MS(3000); EXPECT_DELAY_MS(3000);
if (::stat(fname, &st) != 0) { if (AP::FS().stat(fname, &st) != 0) {
free(fname); free(fname);
return 0; return 0;
} }
@ -699,7 +652,7 @@ int16_t AP_Logger_File::get_log_data(const uint16_t list_entry, const uint16_t p
} }
if (_read_fd != -1 && log_num != _read_fd_log_num) { if (_read_fd != -1 && log_num != _read_fd_log_num) {
::close(_read_fd); AP::FS().close(_read_fd);
_read_fd = -1; _read_fd = -1;
} }
if (_read_fd == -1) { if (_read_fd == -1) {
@ -709,7 +662,7 @@ int16_t AP_Logger_File::get_log_data(const uint16_t list_entry, const uint16_t p
} }
stop_logging(); stop_logging();
EXPECT_DELAY_MS(3000); EXPECT_DELAY_MS(3000);
_read_fd = ::open(fname, O_RDONLY|O_CLOEXEC); _read_fd = AP::FS().open(fname, O_RDONLY);
if (_read_fd == -1) { if (_read_fd == -1) {
_open_error = true; _open_error = true;
int saved_errno = errno; int saved_errno = errno;
@ -736,15 +689,15 @@ int16_t AP_Logger_File::get_log_data(const uint16_t list_entry, const uint16_t p
bug. We can remove this once we find the real bug. bug. We can remove this once we find the real bug.
*/ */
if (ofs / 4096 != (ofs+len) / 4096) { if (ofs / 4096 != (ofs+len) / 4096) {
off_t seek_current = ::lseek(_read_fd, 0, SEEK_CUR); off_t seek_current = AP::FS().lseek(_read_fd, 0, SEEK_CUR);
if (seek_current == (off_t)-1) { if (seek_current == (off_t)-1) {
close(_read_fd); AP::FS().close(_read_fd);
_read_fd = -1; _read_fd = -1;
return -1; return -1;
} }
if (seek_current != (off_t)_read_offset) { if (seek_current != (off_t)_read_offset) {
if (::lseek(_read_fd, _read_offset, SEEK_SET) == (off_t)-1) { if (AP::FS().lseek(_read_fd, _read_offset, SEEK_SET) == (off_t)-1) {
close(_read_fd); AP::FS().close(_read_fd);
_read_fd = -1; _read_fd = -1;
return -1; return -1;
} }
@ -752,14 +705,14 @@ int16_t AP_Logger_File::get_log_data(const uint16_t list_entry, const uint16_t p
} }
if (ofs != _read_offset) { if (ofs != _read_offset) {
if (::lseek(_read_fd, ofs, SEEK_SET) == (off_t)-1) { if (AP::FS().lseek(_read_fd, ofs, SEEK_SET) == (off_t)-1) {
close(_read_fd); AP::FS().close(_read_fd);
_read_fd = -1; _read_fd = -1;
return -1; return -1;
} }
_read_offset = ofs; _read_offset = ofs;
} }
int16_t ret = (int16_t)::read(_read_fd, data, len); int16_t ret = (int16_t)AP::FS().read(_read_fd, data, len);
if (ret > 0) { if (ret > 0) {
_read_offset += ret; _read_offset += ret;
} }
@ -820,7 +773,7 @@ void AP_Logger_File::stop_logging(void)
if (_write_fd != -1) { if (_write_fd != -1) {
int fd = _write_fd; int fd = _write_fd;
_write_fd = -1; _write_fd = -1;
::close(fd); AP::FS().close(fd);
} }
if (have_sem) { if (have_sem) {
write_fd_semaphore.give(); write_fd_semaphore.give();
@ -851,7 +804,7 @@ uint16_t AP_Logger_File::start_new_log(void)
} }
if (_read_fd != -1) { if (_read_fd != -1) {
::close(_read_fd); AP::FS().close(_read_fd);
_read_fd = -1; _read_fd = -1;
} }
@ -891,12 +844,7 @@ uint16_t AP_Logger_File::start_new_log(void)
#endif #endif
EXPECT_DELAY_MS(3000); EXPECT_DELAY_MS(3000);
#if HAL_OS_POSIX_IO _write_fd = AP::FS().open(_write_filename, O_WRONLY|O_CREAT|O_TRUNC);
_write_fd = ::open(_write_filename, O_WRONLY|O_CREAT|O_TRUNC|O_CLOEXEC, 0666);
#else
//TODO add support for mode flags
_write_fd = ::open(_write_filename, O_WRONLY|O_CREAT|O_TRUNC|O_CLOEXEC);
#endif
_cached_oldest_log = 0; _cached_oldest_log = 0;
if (_write_fd == -1) { if (_write_fd == -1) {
@ -921,11 +869,7 @@ uint16_t AP_Logger_File::start_new_log(void)
// we avoid fopen()/fprintf() here as it is not available on as many // we avoid fopen()/fprintf() here as it is not available on as many
// systems as open/write // systems as open/write
EXPECT_DELAY_MS(3000); EXPECT_DELAY_MS(3000);
#if HAL_OS_POSIX_IO int fd = AP::FS().open(fname, O_WRONLY|O_CREAT);
int fd = open(fname, O_WRONLY|O_CREAT|O_CLOEXEC, 0644);
#else
int fd = open(fname, O_WRONLY|O_CREAT|O_CLOEXEC);
#endif
free(fname); free(fname);
if (fd == -1) { if (fd == -1) {
_open_error = true; _open_error = true;
@ -935,8 +879,8 @@ uint16_t AP_Logger_File::start_new_log(void)
char buf[30]; char buf[30];
snprintf(buf, sizeof(buf), "%u\r\n", (unsigned)log_num); snprintf(buf, sizeof(buf), "%u\r\n", (unsigned)log_num);
const ssize_t to_write = strlen(buf); const ssize_t to_write = strlen(buf);
const ssize_t written = write(fd, buf, to_write); const ssize_t written = AP::FS().write(fd, buf, to_write);
close(fd); AP::FS().close(fd);
if (written < to_write) { if (written < to_write) {
_open_error = true; _open_error = true;
@ -1035,7 +979,7 @@ void AP_Logger_File::_io_timer(void)
write_fd_semaphore.give(); write_fd_semaphore.give();
return; return;
} }
ssize_t nwritten = ::write(_write_fd, head, nbytes); ssize_t nwritten = AP::FS().write(_write_fd, head, nbytes);
last_io_operation = ""; last_io_operation = "";
if (nwritten <= 0) { if (nwritten <= 0) {
if (tnow - _last_write_ms > 2000) { if (tnow - _last_write_ms > 2000) {
@ -1044,7 +988,7 @@ void AP_Logger_File::_io_timer(void)
// failures caused by directory listing // failures caused by directory listing
hal.util->perf_count(_perf_errors); hal.util->perf_count(_perf_errors);
last_io_operation = "close"; last_io_operation = "close";
close(_write_fd); AP::FS().close(_write_fd);
last_io_operation = ""; last_io_operation = "";
_write_fd = -1; _write_fd = -1;
_initialised = false; _initialised = false;
@ -1062,7 +1006,7 @@ void AP_Logger_File::_io_timer(void)
*/ */
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE #if CONFIG_HAL_BOARD != HAL_BOARD_SITL && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE
last_io_operation = "fsync"; last_io_operation = "fsync";
::fsync(_write_fd); AP::FS().fsync(_write_fd);
last_io_operation = ""; last_io_operation = "";
#endif #endif
@ -1171,4 +1115,5 @@ void AP_Logger_File::df_stats_log() {
} }
#endif // HAL_OS_POSIX_IO #endif // HAVE_FILESYSTEM_SUPPORT

View File

@ -6,7 +6,9 @@
*/ */
#pragma once #pragma once
#if HAL_OS_POSIX_IO || HAL_OS_FATFS_IO #include <AP_Filesystem/AP_Filesystem.h>
#if HAVE_FILESYSTEM_SUPPORT
#include <AP_HAL/utility/RingBuffer.h> #include <AP_HAL/utility/RingBuffer.h>
#include "AP_Logger_Backend.h" #include "AP_Logger_Backend.h"
@ -179,4 +181,5 @@ private:
}; };
#endif // HAL_OS_POSIX_IO #endif // HAVE_FILESYSTEM_SUPPORT