mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: handle long delays in opening log files
This commit is contained in:
parent
3d386f333f
commit
4e66449b52
|
@ -602,7 +602,9 @@ uint16_t DataFlash_File::find_last_log()
|
||||||
if (fname == nullptr) {
|
if (fname == nullptr) {
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
hal.scheduler->expect_delay_ms(3000);
|
||||||
int fd = open(fname, O_RDONLY|O_CLOEXEC);
|
int fd = open(fname, O_RDONLY|O_CLOEXEC);
|
||||||
|
hal.scheduler->expect_delay_ms(0);
|
||||||
free(fname);
|
free(fname);
|
||||||
if (fd != -1) {
|
if (fd != -1) {
|
||||||
char buf[10];
|
char buf[10];
|
||||||
|
@ -736,7 +738,9 @@ int16_t DataFlash_File::get_log_data(const uint16_t list_entry, const uint16_t p
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
stop_logging();
|
stop_logging();
|
||||||
|
hal.scheduler->expect_delay_ms(3000);
|
||||||
_read_fd = ::open(fname, O_RDONLY|O_CLOEXEC);
|
_read_fd = ::open(fname, O_RDONLY|O_CLOEXEC);
|
||||||
|
hal.scheduler->expect_delay_ms(0);
|
||||||
if (_read_fd == -1) {
|
if (_read_fd == -1) {
|
||||||
_open_error = true;
|
_open_error = true;
|
||||||
int saved_errno = errno;
|
int saved_errno = errno;
|
||||||
|
@ -912,12 +916,14 @@ uint16_t DataFlash_File::start_new_log(void)
|
||||||
write_fd_semaphore->give();
|
write_fd_semaphore->give();
|
||||||
return 0xFFFF;
|
return 0xFFFF;
|
||||||
}
|
}
|
||||||
|
hal.scheduler->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
|
||||||
//TODO add support for mode flags
|
//TODO add support for mode flags
|
||||||
_write_fd = ::open(_write_filename, O_WRONLY|O_CREAT|O_TRUNC|O_CLOEXEC);
|
_write_fd = ::open(_write_filename, O_WRONLY|O_CREAT|O_TRUNC|O_CLOEXEC);
|
||||||
#endif
|
#endif
|
||||||
|
hal.scheduler->expect_delay_ms(0);
|
||||||
_cached_oldest_log = 0;
|
_cached_oldest_log = 0;
|
||||||
|
|
||||||
if (_write_fd == -1) {
|
if (_write_fd == -1) {
|
||||||
|
@ -941,11 +947,13 @@ uint16_t DataFlash_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
|
||||||
|
hal.scheduler->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
|
||||||
int fd = open(fname, O_WRONLY|O_CREAT|O_CLOEXEC);
|
int fd = open(fname, O_WRONLY|O_CREAT|O_CLOEXEC);
|
||||||
#endif
|
#endif
|
||||||
|
hal.scheduler->expect_delay_ms(0);
|
||||||
free(fname);
|
free(fname);
|
||||||
if (fd == -1) {
|
if (fd == -1) {
|
||||||
_open_error = true;
|
_open_error = true;
|
||||||
|
|
Loading…
Reference in New Issue