mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_Logger: use EXPECT_DELAY() macro
This commit is contained in:
parent
02326ac52c
commit
4cdfe6bac3
@ -87,12 +87,11 @@ void AP_Logger_File::Init()
|
||||
_log_directory = custom_dir;
|
||||
}
|
||||
|
||||
hal.scheduler->expect_delay_ms(3000);
|
||||
EXPECT_DELAY(hal, 3000);
|
||||
ret = stat(_log_directory, &st);
|
||||
if (ret == -1) {
|
||||
ret = mkdir(_log_directory, 0777);
|
||||
}
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
if (ret == -1 && errno != EEXIST) {
|
||||
printf("Failed to create log directory %s : %s\n", _log_directory, strerror(errno));
|
||||
}
|
||||
@ -124,14 +123,12 @@ void AP_Logger_File::Init()
|
||||
bool AP_Logger_File::file_exists(const char *filename) const
|
||||
{
|
||||
struct stat st;
|
||||
hal.scheduler->expect_delay_ms(3000);
|
||||
EXPECT_DELAY(hal, 3000);
|
||||
if (stat(filename, &st) == -1) {
|
||||
// hopefully errno==ENOENT. If some error occurs it is
|
||||
// probably better to assume this file exists.
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
return false;
|
||||
}
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
return true;
|
||||
}
|
||||
|
||||
@ -259,18 +256,17 @@ uint16_t AP_Logger_File::find_oldest_log()
|
||||
// We could count up to find_last_log(), but if people start
|
||||
// relying on the min_avail_space_percent feature we could end up
|
||||
// doing a *lot* of asprintf()s and stat()s
|
||||
hal.scheduler->expect_delay_ms(3000);
|
||||
EXPECT_DELAY(hal, 3000);
|
||||
DIR *d = opendir(_log_directory);
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
if (d == nullptr) {
|
||||
// SD card may have died? On linux someone may have rm-rf-d
|
||||
return 0;
|
||||
}
|
||||
|
||||
// we only remove files which look like xxx.BIN
|
||||
hal.scheduler->expect_delay_ms(3000);
|
||||
EXPECT_DELAY(hal, 3000);
|
||||
for (struct dirent *de=readdir(d); de; de=readdir(d)) {
|
||||
hal.scheduler->expect_delay_ms(3000);
|
||||
EXPECT_DELAY(hal, 3000);
|
||||
uint8_t length = strlen(de->d_name);
|
||||
if (length < 5) {
|
||||
// not long enough for \d+[.]BIN
|
||||
@ -305,7 +301,6 @@ uint16_t AP_Logger_File::find_oldest_log()
|
||||
}
|
||||
}
|
||||
closedir(d);
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
_cached_oldest_log = current_oldest_log;
|
||||
|
||||
return current_oldest_log;
|
||||
@ -349,7 +344,7 @@ void AP_Logger_File::Prep_MinSpace()
|
||||
if (file_exists(filename_to_remove)) {
|
||||
hal.console->printf("Removing (%s) for minimum-space requirements (%.2f%% < %.0f%%)\n",
|
||||
filename_to_remove, (double)avail, (double)min_avail_space_percent);
|
||||
hal.scheduler->expect_delay_ms(2000);
|
||||
EXPECT_DELAY(hal, 2000);
|
||||
if (unlink(filename_to_remove) == -1) {
|
||||
hal.console->printf("Failed to remove %s: %s\n", filename_to_remove, strerror(errno));
|
||||
free(filename_to_remove);
|
||||
@ -363,7 +358,6 @@ void AP_Logger_File::Prep_MinSpace()
|
||||
} else {
|
||||
free(filename_to_remove);
|
||||
}
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
}
|
||||
log_to_remove++;
|
||||
if (log_to_remove > MAX_LOG_FILES) {
|
||||
@ -477,9 +471,8 @@ void AP_Logger_File::EraseAll()
|
||||
if (fname == nullptr) {
|
||||
break;
|
||||
}
|
||||
hal.scheduler->expect_delay_ms(3000);
|
||||
EXPECT_DELAY(hal, 3000);
|
||||
unlink(fname);
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
free(fname);
|
||||
}
|
||||
char *fname = _lastlog_file_name();
|
||||
@ -577,9 +570,8 @@ uint16_t AP_Logger_File::find_last_log()
|
||||
if (fname == nullptr) {
|
||||
return ret;
|
||||
}
|
||||
hal.scheduler->expect_delay_ms(3000);
|
||||
EXPECT_DELAY(hal, 3000);
|
||||
int fd = open(fname, O_RDONLY|O_CLOEXEC);
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
free(fname);
|
||||
if (fd != -1) {
|
||||
char buf[10];
|
||||
@ -612,14 +604,12 @@ uint32_t AP_Logger_File::_get_log_size(const uint16_t log_num)
|
||||
write_fd_semaphore.give();
|
||||
}
|
||||
struct stat st;
|
||||
hal.scheduler->expect_delay_ms(3000);
|
||||
EXPECT_DELAY(hal, 3000);
|
||||
if (::stat(fname, &st) != 0) {
|
||||
printf("Unable to fetch Log File Size: %s\n", strerror(errno));
|
||||
free(fname);
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
return 0;
|
||||
}
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
free(fname);
|
||||
return st.st_size;
|
||||
}
|
||||
@ -644,14 +634,12 @@ uint32_t AP_Logger_File::_get_log_time(const uint16_t log_num)
|
||||
write_fd_semaphore.give();
|
||||
}
|
||||
struct stat st;
|
||||
hal.scheduler->expect_delay_ms(3000);
|
||||
EXPECT_DELAY(hal, 3000);
|
||||
if (::stat(fname, &st) != 0) {
|
||||
free(fname);
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
return 0;
|
||||
}
|
||||
free(fname);
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
return st.st_mtime;
|
||||
}
|
||||
|
||||
@ -719,9 +707,8 @@ int16_t AP_Logger_File::get_log_data(const uint16_t list_entry, const uint16_t p
|
||||
return -1;
|
||||
}
|
||||
stop_logging();
|
||||
hal.scheduler->expect_delay_ms(3000);
|
||||
EXPECT_DELAY(hal, 3000);
|
||||
_read_fd = ::open(fname, O_RDONLY|O_CLOEXEC);
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
if (_read_fd == -1) {
|
||||
_open_error = true;
|
||||
int saved_errno = errno;
|
||||
@ -897,14 +884,13 @@ uint16_t AP_Logger_File::start_new_log(void)
|
||||
write_fd_semaphore.give();
|
||||
return 0xFFFF;
|
||||
}
|
||||
hal.scheduler->expect_delay_ms(3000);
|
||||
EXPECT_DELAY(hal, 3000);
|
||||
#if HAL_OS_POSIX_IO
|
||||
_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
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
_cached_oldest_log = 0;
|
||||
|
||||
if (_write_fd == -1) {
|
||||
@ -928,13 +914,12 @@ uint16_t AP_Logger_File::start_new_log(void)
|
||||
|
||||
// we avoid fopen()/fprintf() here as it is not available on as many
|
||||
// systems as open/write
|
||||
hal.scheduler->expect_delay_ms(3000);
|
||||
EXPECT_DELAY(hal, 3000);
|
||||
#if HAL_OS_POSIX_IO
|
||||
int fd = open(fname, O_WRONLY|O_CREAT|O_CLOEXEC, 0644);
|
||||
#else
|
||||
int fd = open(fname, O_WRONLY|O_CREAT|O_CLOEXEC);
|
||||
#endif
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
free(fname);
|
||||
if (fd == -1) {
|
||||
_open_error = true;
|
||||
|
Loading…
Reference in New Issue
Block a user