mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Logger: rename to EXPECT_DELAY_MS()
This commit is contained in:
parent
3823ba539c
commit
6fa69c2297
@ -87,7 +87,7 @@ void AP_Logger_File::Init()
|
|||||||
_log_directory = custom_dir;
|
_log_directory = custom_dir;
|
||||||
}
|
}
|
||||||
|
|
||||||
EXPECT_DELAY(hal, 3000);
|
EXPECT_DELAY_MS(3000);
|
||||||
ret = stat(_log_directory, &st);
|
ret = stat(_log_directory, &st);
|
||||||
if (ret == -1) {
|
if (ret == -1) {
|
||||||
ret = mkdir(_log_directory, 0777);
|
ret = mkdir(_log_directory, 0777);
|
||||||
@ -123,7 +123,7 @@ void AP_Logger_File::Init()
|
|||||||
bool AP_Logger_File::file_exists(const char *filename) const
|
bool AP_Logger_File::file_exists(const char *filename) const
|
||||||
{
|
{
|
||||||
struct stat st;
|
struct stat st;
|
||||||
EXPECT_DELAY(hal, 3000);
|
EXPECT_DELAY_MS(3000);
|
||||||
if (stat(filename, &st) == -1) {
|
if (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.
|
||||||
@ -256,7 +256,7 @@ uint16_t AP_Logger_File::find_oldest_log()
|
|||||||
// We could count up to find_last_log(), but if people start
|
// We could count up to find_last_log(), but if people start
|
||||||
// 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(hal, 3000);
|
EXPECT_DELAY_MS(3000);
|
||||||
DIR *d = opendir(_log_directory);
|
DIR *d = 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
|
||||||
@ -264,9 +264,9 @@ 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(hal, 3000);
|
EXPECT_DELAY_MS(3000);
|
||||||
for (struct dirent *de=readdir(d); de; de=readdir(d)) {
|
for (struct dirent *de=readdir(d); de; de=readdir(d)) {
|
||||||
EXPECT_DELAY(hal, 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) {
|
||||||
// not long enough for \d+[.]BIN
|
// not long enough for \d+[.]BIN
|
||||||
@ -344,7 +344,7 @@ void AP_Logger_File::Prep_MinSpace()
|
|||||||
if (file_exists(filename_to_remove)) {
|
if (file_exists(filename_to_remove)) {
|
||||||
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(hal, 2000);
|
EXPECT_DELAY_MS(2000);
|
||||||
if (unlink(filename_to_remove) == -1) {
|
if (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);
|
||||||
@ -471,7 +471,7 @@ void AP_Logger_File::EraseAll()
|
|||||||
if (fname == nullptr) {
|
if (fname == nullptr) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
EXPECT_DELAY(hal, 3000);
|
EXPECT_DELAY_MS(3000);
|
||||||
unlink(fname);
|
unlink(fname);
|
||||||
free(fname);
|
free(fname);
|
||||||
}
|
}
|
||||||
@ -570,7 +570,7 @@ uint16_t AP_Logger_File::find_last_log()
|
|||||||
if (fname == nullptr) {
|
if (fname == nullptr) {
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
EXPECT_DELAY(hal, 3000);
|
EXPECT_DELAY_MS(3000);
|
||||||
int fd = open(fname, O_RDONLY|O_CLOEXEC);
|
int fd = open(fname, O_RDONLY|O_CLOEXEC);
|
||||||
free(fname);
|
free(fname);
|
||||||
if (fd != -1) {
|
if (fd != -1) {
|
||||||
@ -604,7 +604,7 @@ uint32_t AP_Logger_File::_get_log_size(const uint16_t log_num)
|
|||||||
write_fd_semaphore.give();
|
write_fd_semaphore.give();
|
||||||
}
|
}
|
||||||
struct stat st;
|
struct stat st;
|
||||||
EXPECT_DELAY(hal, 3000);
|
EXPECT_DELAY_MS(3000);
|
||||||
if (::stat(fname, &st) != 0) {
|
if (::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);
|
||||||
@ -634,7 +634,7 @@ uint32_t AP_Logger_File::_get_log_time(const uint16_t log_num)
|
|||||||
write_fd_semaphore.give();
|
write_fd_semaphore.give();
|
||||||
}
|
}
|
||||||
struct stat st;
|
struct stat st;
|
||||||
EXPECT_DELAY(hal, 3000);
|
EXPECT_DELAY_MS(3000);
|
||||||
if (::stat(fname, &st) != 0) {
|
if (::stat(fname, &st) != 0) {
|
||||||
free(fname);
|
free(fname);
|
||||||
return 0;
|
return 0;
|
||||||
@ -707,7 +707,7 @@ int16_t AP_Logger_File::get_log_data(const uint16_t list_entry, const uint16_t p
|
|||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
stop_logging();
|
stop_logging();
|
||||||
EXPECT_DELAY(hal, 3000);
|
EXPECT_DELAY_MS(3000);
|
||||||
_read_fd = ::open(fname, O_RDONLY|O_CLOEXEC);
|
_read_fd = ::open(fname, O_RDONLY|O_CLOEXEC);
|
||||||
if (_read_fd == -1) {
|
if (_read_fd == -1) {
|
||||||
_open_error = true;
|
_open_error = true;
|
||||||
@ -884,7 +884,7 @@ uint16_t AP_Logger_File::start_new_log(void)
|
|||||||
write_fd_semaphore.give();
|
write_fd_semaphore.give();
|
||||||
return 0xFFFF;
|
return 0xFFFF;
|
||||||
}
|
}
|
||||||
EXPECT_DELAY(hal, 3000);
|
EXPECT_DELAY_MS(3000);
|
||||||
#if HAL_OS_POSIX_IO
|
#if HAL_OS_POSIX_IO
|
||||||
_write_fd = ::open(_write_filename, O_WRONLY|O_CREAT|O_TRUNC|O_CLOEXEC, 0666);
|
_write_fd = ::open(_write_filename, O_WRONLY|O_CREAT|O_TRUNC|O_CLOEXEC, 0666);
|
||||||
#else
|
#else
|
||||||
@ -914,7 +914,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(hal, 3000);
|
EXPECT_DELAY_MS(3000);
|
||||||
#if HAL_OS_POSIX_IO
|
#if HAL_OS_POSIX_IO
|
||||||
int fd = open(fname, O_WRONLY|O_CREAT|O_CLOEXEC, 0644);
|
int fd = open(fname, O_WRONLY|O_CREAT|O_CLOEXEC, 0644);
|
||||||
#else
|
#else
|
||||||
|
Loading…
Reference in New Issue
Block a user