2 AP_Logger logging - file oriented variant
4 This uses posix file IO to create log files called logs/NN.bin in the
7 SD Card Rates on PixHawk:
8 - deletion rate seems to be ~50 files/second.
9 - stat seems to be ~150/second
10 - readdir loop of 511 entry directory ~62,000 microseconds
13 #include "AP_Logger_config.h"
15 #if HAL_LOGGING_FILESYSTEM_ENABLED
17 #include <AP_HAL/AP_HAL.h>
18 #include <AP_Filesystem/AP_Filesystem.h>
19 #if AP_FILESYSTEM_LITTLEFS_ENABLED
20 #include <AP_Filesystem/AP_Filesystem_FlashMemory_LittleFS.h>
23 #include "AP_Logger.h"
24 #include "AP_Logger_File.h"
26 #include <AP_Common/AP_Common.h>
27 #include <AP_InternalError/AP_InternalError.h>
28 #include <AP_RTC/AP_RTC.h>
29 #include <AP_Vehicle/AP_Vehicle_Type.h>
30 #include <AP_AHRS/AP_AHRS.h>
32 #include <AP_Math/AP_Math.h>
33 #include <GCS_MAVLink/GCS.h>
37 extern const AP_HAL::HAL
& hal
;
39 #define LOGGER_PAGE_SIZE 1024UL
41 #define MB_to_B 1000000
42 #define B_to_MB 0.000001
44 // time between tries to open log
45 #define LOGGER_FILE_REOPEN_MS 5000
50 AP_Logger_File::AP_Logger_File(AP_Logger
&front
,
51 LoggerMessageWriter_DFLogStart
*writer
) :
52 AP_Logger_Backend(front
, writer
),
53 _log_directory(HAL_BOARD_LOG_DIRECTORY
)
59 void AP_Logger_File::ensure_log_directory_exists()
64 EXPECT_DELAY_MS(3000);
65 ret
= AP::FS().stat(_log_directory
, &st
);
67 ret
= AP::FS().mkdir(_log_directory
);
69 if (ret
== -1 && errno
!= EEXIST
) {
70 GCS_SEND_TEXT(MAV_SEVERITY_WARNING
, "Failed to create log directory %s : %s", _log_directory
, strerror(errno
));
74 void AP_Logger_File::Init()
76 // determine and limit file backend buffersize
77 uint32_t bufsize
= _front
._params
.file_bufsize
;
80 const uint32_t desired_bufsize
= bufsize
;
82 // If we can't allocate the full size, try to reduce it until we can allocate it
83 while (!_writebuf
.set_size(bufsize
) && bufsize
>= _writebuf_chunk
) {
86 if (bufsize
>= _writebuf_chunk
&& bufsize
!= desired_bufsize
) {
87 DEV_PRINTF("AP_Logger: reduced buffer %u/%u\n", (unsigned)bufsize
, (unsigned)desired_bufsize
);
90 if (!_writebuf
.get_size()) {
91 DEV_PRINTF("Out of memory for logging\n");
95 DEV_PRINTF("AP_Logger_File: buffer size=%u\n", (unsigned)bufsize
);
99 const char* custom_dir
= hal
.util
->get_custom_log_directory();
100 if (custom_dir
!= nullptr){
101 _log_directory
= custom_dir
;
104 uint16_t last_log_num
= find_last_log();
105 if (last_log_is_marked_discard
) {
106 // delete the last log leftover from LOG_DISARMED=3
107 char *filename
= _log_file_name(last_log_num
);
108 if (filename
!= nullptr) {
109 AP::FS().unlink(filename
);
117 bool AP_Logger_File::file_exists(const char *filename
) const
120 EXPECT_DELAY_MS(3000);
121 if (AP::FS().stat(filename
, &st
) == -1) {
122 // hopefully errno==ENOENT. If some error occurs it is
123 // probably better to assume this file exists.
129 bool AP_Logger_File::log_exists(const uint16_t lognum
) const
131 char *filename
= _log_file_name(lognum
);
132 if (filename
== nullptr) {
135 bool ret
= file_exists(filename
);
140 void AP_Logger_File::periodic_1Hz()
142 AP_Logger_Backend::periodic_1Hz();
145 _write_fd
== -1 && _read_fd
== -1 &&
146 erase
.log_num
== 0 &&
148 // restart logging after an erase if needed
149 erase
.was_logging
= false;
150 // setup to open the log in the backend thread
151 start_new_log_pending
= true;
155 !start_new_log_pending
&&
156 _write_fd
== -1 && _read_fd
== -1 &&
158 !recent_open_error()) {
159 // setup to open the log in the backend thread
160 start_new_log_pending
= true;
163 if (!io_thread_alive()) {
164 if (io_thread_warning_decimation_counter
== 0 && _initialised
) {
165 // we don't print this error unless we did initialise. When _initialised is set to true
166 // we register the IO timer callback
167 GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL
, "AP_Logger: stuck thread (%s)", last_io_operation
);
169 if (io_thread_warning_decimation_counter
++ > 30) {
170 io_thread_warning_decimation_counter
= 0;
174 if (rate_limiter
== nullptr &&
175 (_front
._params
.file_ratemax
> 0 ||
176 _front
._params
.disarm_ratemax
> 0 ||
177 _front
._log_pause
)) {
178 // setup rate limiting if log rate max > 0Hz or log pause of streaming entries is requested
179 rate_limiter
= NEW_NOTHROW
AP_Logger_RateLimiter(_front
, _front
._params
.file_ratemax
, _front
._params
.disarm_ratemax
);
183 void AP_Logger_File::periodic_fullrate()
185 AP_Logger_Backend::push_log_blocks();
188 uint32_t AP_Logger_File::bufferspace_available()
190 const uint32_t space
= _writebuf
.space();
191 const uint32_t crit
= critical_message_reserved_space(_writebuf
.get_size());
193 return (space
> crit
) ? space
- crit
: 0;
196 bool AP_Logger_File::recent_open_error(void) const
198 if (_open_error_ms
== 0) {
201 return AP_HAL::millis() - _open_error_ms
< LOGGER_FILE_REOPEN_MS
;
204 // return true for CardInserted() if we successfully initialized
205 bool AP_Logger_File::CardInserted(void) const
207 return _initialised
&& !recent_open_error();
210 // returns the amount of disk space available in _log_directory (in bytes)
211 // returns -1 on error
212 int64_t AP_Logger_File::disk_space_avail()
214 return AP::FS().disk_free(_log_directory
);
217 // returns the total amount of disk space (in use + available) in
218 // _log_directory (in bytes).
219 // returns -1 on error
220 int64_t AP_Logger_File::disk_space()
222 return AP::FS().disk_space(_log_directory
);
226 convert a dirent to a log number
228 bool AP_Logger_File::dirent_to_log_num(const dirent
*de
, uint16_t &log_num
) const
230 uint8_t length
= strlen(de
->d_name
);
234 if (strncmp(&de
->d_name
[length
-4], ".BIN", 4) != 0) {
235 // doesn't end in .BIN
239 uint16_t thisnum
= strtoul(de
->d_name
, nullptr, 10);
240 if (thisnum
> _front
.get_max_num_logs()) {
248 // find_oldest_log - find oldest log in _log_directory
249 // returns 0 if no log was found
250 uint16_t AP_Logger_File::find_oldest_log()
252 if (_cached_oldest_log
!= 0) {
253 return _cached_oldest_log
;
256 uint16_t last_log_num
= find_last_log();
257 if (last_log_num
== 0) {
261 uint16_t current_oldest_log
= 0; // 0 is invalid
263 // We could count up to find_last_log(), but if people start
264 // relying on the min_avail_space_percent feature we could end up
265 // doing a *lot* of asprintf()s and stat()s
266 EXPECT_DELAY_MS(3000);
267 auto *d
= AP::FS().opendir(_log_directory
);
269 // SD card may have died? On linux someone may have rm-rf-d
273 // we only remove files which look like xxx.BIN
274 EXPECT_DELAY_MS(3000);
275 for (struct dirent
*de
=AP::FS().readdir(d
); de
; de
=AP::FS().readdir(d
)) {
276 EXPECT_DELAY_MS(3000);
278 if (!dirent_to_log_num(de
, thisnum
)) {
279 // not a log filename
282 if (current_oldest_log
== 0) {
283 current_oldest_log
= thisnum
;
285 if (current_oldest_log
<= last_log_num
) {
286 if (thisnum
> last_log_num
) {
287 current_oldest_log
= thisnum
;
288 } else if (thisnum
< current_oldest_log
) {
289 current_oldest_log
= thisnum
;
291 } else { // current_oldest_log > last_log_num
292 if (thisnum
> last_log_num
) {
293 if (thisnum
< current_oldest_log
) {
294 current_oldest_log
= thisnum
;
300 AP::FS().closedir(d
);
301 _cached_oldest_log
= current_oldest_log
;
303 return current_oldest_log
;
306 void AP_Logger_File::Prep_MinSpace()
308 if (hal
.util
->was_watchdog_reset()) {
309 // don't clear space if watchdog reset, it takes too long
313 if (!CardInserted()) {
317 const uint16_t first_log_to_remove
= find_oldest_log();
318 if (first_log_to_remove
== 0) {
319 // no files to remove
323 const int64_t target_free
= (int64_t)_front
._params
.min_MB_free
* MB_to_B
;
325 uint16_t log_to_remove
= first_log_to_remove
;
329 int64_t avail
= disk_space_avail();
333 if (avail
>= target_free
) {
336 if (count
++ > _front
.get_max_num_logs() + 10) {
337 // *way* too many deletions going on here. Possible internal error.
338 INTERNAL_ERROR(AP_InternalError::error_t::logger_too_many_deletions
);
341 char *filename_to_remove
= _log_file_name(log_to_remove
);
342 if (filename_to_remove
== nullptr) {
343 INTERNAL_ERROR(AP_InternalError::error_t::logger_bad_getfilename
);
346 if (file_exists(filename_to_remove
)) {
347 DEV_PRINTF("Removing (%s) for minimum-space requirements (%.0fMB < %.0fMB)\n",
348 filename_to_remove
, (double)avail
*B_to_MB
, (double)target_free
*B_to_MB
);
349 EXPECT_DELAY_MS(2000);
350 if (AP::FS().unlink(filename_to_remove
) == -1) {
351 _cached_oldest_log
= 0;
352 DEV_PRINTF("Failed to remove %s: %s\n", filename_to_remove
, strerror(errno
));
353 free(filename_to_remove
);
354 if (errno
== ENOENT
) {
355 // corruption - should always have a continuous
356 // sequence of files... however, there may be still
357 // files out there, so keep going.
362 free(filename_to_remove
);
366 if (log_to_remove
> _front
.get_max_num_logs()) {
369 } while (log_to_remove
!= first_log_to_remove
);
373 construct a log file name given a log number.
374 The number in the log filename will be zero-padded.
375 Note: Caller must free.
377 char *AP_Logger_File::_log_file_name(const uint16_t log_num
) const
380 if (asprintf(&buf
, "%s/%08u.BIN", _log_directory
, (unsigned)log_num
) == -1) {
387 return path name of the lastlog.txt marker file
388 Note: Caller must free.
390 char *AP_Logger_File::_lastlog_file_name(void) const
393 if (asprintf(&buf
, "%s/LASTLOG.TXT", _log_directory
) == -1) {
400 // remove all log files
401 void AP_Logger_File::EraseAll()
403 if (hal
.util
->get_soft_armed()) {
404 // do not want to do any filesystem operations while we are e.g. flying
411 erase
.was_logging
= (_write_fd
!= -1);
417 bool AP_Logger_File::WritesOK() const
419 if (_write_fd
== -1) {
422 if (recent_open_error()) {
429 bool AP_Logger_File::StartNewLogOK() const
431 if (recent_open_error()) {
434 #if !APM_BUILD_TYPE(APM_BUILD_Replay) && !APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
435 if (hal
.scheduler
->in_main_thread()) {
439 return AP_Logger_Backend::StartNewLogOK();
442 /* Write a block of data at current offset */
443 bool AP_Logger_File::_WritePrioritisedBlock(const void *pBuffer
, uint16_t size
, bool is_critical
)
445 WITH_SEMAPHORE(semaphore
);
447 #if APM_BUILD_TYPE(APM_BUILD_Replay)
448 if (AP::FS().write(_write_fd
, pBuffer
, size
) != size
) {
449 AP_HAL::panic("Short write");
455 uint32_t space
= _writebuf
.space();
457 if (_writing_startup_messages
&&
458 _startup_messagewriter
->fmt_done()) {
459 // the state machine has called us, and it has finished
460 // writing format messages out. It can always get back to us
461 // with more messages later, so let's leave room for other
463 const uint32_t now
= AP_HAL::millis();
464 const bool must_dribble
= (now
- last_messagewrite_message_sent
) > 100;
466 space
< non_messagewriter_message_reserved_space(_writebuf
.get_size())) {
467 // this message isn't dropped, it will be sent again...
470 last_messagewrite_message_sent
= now
;
472 // we reserve some amount of space for critical messages:
473 if (!is_critical
&& space
< critical_message_reserved_space(_writebuf
.get_size())) {
479 // if no room for entire message - drop it:
485 _writebuf
.write((uint8_t*)pBuffer
, size
);
486 df_stats_gather(size
, _writebuf
.space());
491 find the highest log number
493 uint16_t AP_Logger_File::find_last_log()
496 char *fname
= _lastlog_file_name();
497 if (fname
== nullptr) {
500 EXPECT_DELAY_MS(3000);
501 FileData
*fd
= AP::FS().load_file(fname
);
503 last_log_is_marked_discard
= false;
505 char *endptr
= nullptr;
506 ret
= strtol((const char *)fd
->data
, &endptr
, 10);
507 if (endptr
!= nullptr) {
508 last_log_is_marked_discard
= *endptr
== 'D';
515 uint32_t AP_Logger_File::_get_log_size(const uint16_t log_num
)
517 char *fname
= _log_file_name(log_num
);
518 if (fname
== nullptr) {
521 if (_write_fd
!= -1 && write_fd_semaphore
.take_nonblocking()) {
522 if (_write_filename
!= nullptr && strcmp(_write_filename
, fname
) == 0) {
523 // it is the file we are currently writing
525 write_fd_semaphore
.give();
526 return _write_offset
;
528 write_fd_semaphore
.give();
531 EXPECT_DELAY_MS(3000);
532 if (AP::FS().stat(fname
, &st
) != 0) {
540 uint32_t AP_Logger_File::_get_log_time(const uint16_t log_num
)
542 char *fname
= _log_file_name(log_num
);
543 if (fname
== nullptr) {
546 if (_write_fd
!= -1 && write_fd_semaphore
.take_nonblocking()) {
547 if (_write_filename
!= nullptr && strcmp(_write_filename
, fname
) == 0) {
548 // it is the file we are currently writing
550 write_fd_semaphore
.give();
553 if (!AP::rtc().get_utc_usec(utc_usec
)) {
556 return utc_usec
/ 1000000U;
561 write_fd_semaphore
.give();
564 EXPECT_DELAY_MS(3000);
565 if (AP::FS().stat(fname
, &st
) != 0) {
574 find the number of pages in a log
576 void AP_Logger_File::get_log_boundaries(const uint16_t list_entry
, uint32_t & start_page
, uint32_t & end_page
)
578 const uint16_t log_num
= log_num_from_list_entry(list_entry
);
580 // that failed - probably no logs
587 end_page
= _get_log_size(log_num
) / LOGGER_PAGE_SIZE
;
591 retrieve data from a log file
593 int16_t AP_Logger_File::get_log_data(const uint16_t list_entry
, const uint16_t page
, const uint32_t offset
, const uint16_t len
, uint8_t *data
)
595 if (!_initialised
|| recent_open_error()) {
599 const uint16_t log_num
= log_num_from_list_entry(list_entry
);
601 // that failed - probably no logs
605 if (_read_fd
!= -1 && log_num
!= _read_fd_log_num
) {
606 AP::FS().close(_read_fd
);
609 if (_read_fd
== -1) {
610 char *fname
= _log_file_name(log_num
);
611 if (fname
== nullptr) {
615 EXPECT_DELAY_MS(3000);
616 _read_fd
= AP::FS().open(fname
, O_RDONLY
);
617 if (_read_fd
== -1) {
618 _open_error_ms
= AP_HAL::millis();
619 int saved_errno
= errno
;
620 ::printf("Log read open fail for %s - %s\n",
621 fname
, strerror(saved_errno
));
622 DEV_PRINTF("Log read open fail for %s - %s\n",
623 fname
, strerror(saved_errno
));
629 _read_fd_log_num
= log_num
;
631 uint32_t ofs
= page
* (uint32_t)LOGGER_PAGE_SIZE
+ offset
;
633 if (ofs
!= _read_offset
) {
634 if (AP::FS().lseek(_read_fd
, ofs
, SEEK_SET
) == (off_t
)-1) {
635 AP::FS().close(_read_fd
);
641 int16_t ret
= (int16_t)AP::FS().read(_read_fd
, data
, len
);
648 void AP_Logger_File::end_log_transfer()
650 if (_read_fd
!= -1) {
651 AP::FS().close(_read_fd
);
657 find size and date of a log
659 void AP_Logger_File::get_log_info(const uint16_t list_entry
, uint32_t &size
, uint32_t &time_utc
)
661 uint16_t log_num
= log_num_from_list_entry(list_entry
);
663 // that failed - probably no logs
669 size
= _get_log_size(log_num
);
670 time_utc
= _get_log_time(log_num
);
675 get the number of logs - note that the log numbers must be consecutive
677 uint16_t AP_Logger_File::get_num_logs()
679 auto *d
= AP::FS().opendir(_log_directory
);
683 uint16_t high
= find_last_log();
685 uint16_t smallest_above_last
= 0;
687 EXPECT_DELAY_MS(2000);
688 for (struct dirent
*de
=AP::FS().readdir(d
); de
; de
=AP::FS().readdir(d
)) {
689 EXPECT_DELAY_MS(100);
691 if (!dirent_to_log_num(de
, thisnum
)) {
692 // not a log filename
696 if (thisnum
> high
&& (smallest_above_last
== 0 || thisnum
< smallest_above_last
)) {
697 smallest_above_last
= thisnum
;
700 AP::FS().closedir(d
);
701 if (smallest_above_last
!= 0) {
702 // we have wrapped, add in the logs with high numbers
703 ret
+= (_front
.get_max_num_logs() - smallest_above_last
) + 1;
712 void AP_Logger_File::stop_logging(void)
714 // best-case effort to avoid annoying the IO thread
715 const bool have_sem
= write_fd_semaphore
.take(hal
.util
->get_soft_armed()?1:20);
716 if (_write_fd
!= -1) {
722 write_fd_semaphore
.give();
727 does start_new_log in the logger thread
729 void AP_Logger_File::PrepForArming_start_logging()
731 if (logging_started()) {
735 uint32_t start_ms
= AP_HAL::millis();
736 const uint32_t open_limit_ms
= 1000;
739 log open happens in the io_timer thread. We allow for a maximum
740 of 1s to complete the open
742 start_new_log_pending
= true;
743 EXPECT_DELAY_MS(1000);
744 while (AP_HAL::millis() - start_ms
< open_limit_ms
) {
745 if (logging_started()) {
748 #if !APM_BUILD_TYPE(APM_BUILD_Replay) && AP_AHRS_ENABLED
749 // keep the EKF ticking over
752 hal
.scheduler
->delay(1);
757 start writing to a new log file
759 void AP_Logger_File::start_new_log(void)
761 if (recent_open_error()) {
762 // we have previously failed to open a file - don't try again
763 // to prevent us trying to open files while in flight
767 if (erase
.log_num
!= 0) {
768 // don't start a new log while erasing, but record that we
769 // want to start logging when erase finished
770 erase
.was_logging
= true;
774 const bool open_error_ms_was_zero
= (_open_error_ms
== 0);
776 // set _open_error here to avoid infinite recursion. Simply
777 // writing a prioritised block may try to open a log - which means
778 // if anything in the start_new_log path does a GCS_SEND_TEXT()
779 // (for example), you will end up recursing if we don't take
780 // precautions. We will reset _open_error if we actually manage
781 // to open the log...
782 _open_error_ms
= AP_HAL::millis();
786 start_new_log_reset_variables();
788 if (_read_fd
!= -1) {
789 AP::FS().close(_read_fd
);
793 if (disk_space_avail() < _free_space_min_avail
&& disk_space() > 0) {
794 DEV_PRINTF("Out of space for logging\n");
798 uint16_t log_num
= find_last_log();
799 // re-use empty logs if possible
800 if (_get_log_size(log_num
) > 0 || log_num
== 0) {
803 if (log_num
> _front
.get_max_num_logs()) {
806 if (!write_fd_semaphore
.take(1)) {
809 if (_write_filename
) {
810 free(_write_filename
);
811 _write_filename
= nullptr;
813 _write_filename
= _log_file_name(log_num
);
814 if (_write_filename
== nullptr) {
815 write_fd_semaphore
.give();
819 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
820 // remember if we had utc time when we opened the file
823 _need_rtc_update
= !AP::rtc().get_utc_usec(utc_usec
);
827 // create the log directory if need be
828 ensure_log_directory_exists();
830 EXPECT_DELAY_MS(3000);
831 _write_fd
= AP::FS().open(_write_filename
, O_WRONLY
|O_CREAT
|O_TRUNC
);
832 _cached_oldest_log
= 0;
834 if (_write_fd
== -1) {
835 write_fd_semaphore
.give();
836 int saved_errno
= errno
;
837 if (open_error_ms_was_zero
) {
838 ::printf("Log open fail for %s - %s\n",
839 _write_filename
, strerror(saved_errno
));
840 DEV_PRINTF("Log open fail for %s - %s\n",
841 _write_filename
, strerror(saved_errno
));
845 _last_write_ms
= AP_HAL::millis();
849 write_fd_semaphore
.give();
851 // now update lastlog.txt with the new log number
852 last_log_is_marked_discard
= _front
._params
.log_disarmed
== AP_Logger::LogDisarmed::LOG_WHILE_DISARMED_DISCARD
;
853 if (!write_lastlog_file(log_num
)) {
854 _open_error_ms
= AP_HAL::millis();
859 write LASTLOG.TXT, possibly with a discard marker
861 bool AP_Logger_File::write_lastlog_file(uint16_t log_num
)
863 // now update lastlog.txt with the new log number
864 char *fname
= _lastlog_file_name();
866 EXPECT_DELAY_MS(3000);
867 int fd
= AP::FS().open(fname
, O_WRONLY
|O_CREAT
);
874 snprintf(buf
, sizeof(buf
), "%u%s\r\n", (unsigned)log_num
, last_log_is_marked_discard
?"D":"");
875 const ssize_t to_write
= strlen(buf
);
876 const ssize_t written
= AP::FS().write(fd
, buf
, to_write
);
878 return written
== to_write
;
881 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
882 void AP_Logger_File::flush(void)
883 #if APM_BUILD_TYPE(APM_BUILD_Replay) || APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
885 uint32_t tnow
= AP_HAL::millis();
886 while (_write_fd
!= -1 && _initialised
&& !recent_open_error() && _writebuf
.available()) {
887 // convince the IO timer that it really is OK to write out
888 // less than _writebuf_chunk bytes:
889 if (tnow
> 2001) { // avoid resetting _last_write_time to 0
890 _last_write_time
= tnow
- 2001;
894 if (write_fd_semaphore
.take(1)) {
895 if (_write_fd
!= -1) {
898 write_fd_semaphore
.give();
900 INTERNAL_ERROR(AP_InternalError::error_t::logger_flushing_without_sem
);
905 // flush is for replay and examples only
907 #endif // APM_BUILD_TYPE(APM_BUILD_Replay) || APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
910 void AP_Logger_File::io_timer(void)
912 uint32_t tnow
= AP_HAL::millis();
913 _io_timer_heartbeat
= tnow
;
915 if (start_new_log_pending
) {
917 start_new_log_pending
= false;
920 if (erase
.log_num
!= 0) {
926 if (_write_fd
== -1 || !_initialised
|| recent_open_error()) {
930 if (last_log_is_marked_discard
&& hal
.util
->get_soft_armed()) {
931 // time to make the log permanent
932 const auto log_num
= find_last_log();
933 last_log_is_marked_discard
= false;
934 write_lastlog_file(log_num
);
937 uint32_t nbytes
= _writebuf
.available();
941 if (nbytes
< _writebuf_chunk
&&
942 tnow
- _last_write_time
< 2000UL) {
943 // write in _writebuf_chunk-sized chunks, but always write at
944 // least once per 2 seconds if data is available
948 #if !AP_FILESYSTEM_LITTLEFS_ENABLED // too expensive on littlefs, rely on ENOSPC below
949 if (tnow
- _free_space_last_check_time
> _free_space_check_interval
) {
950 _free_space_last_check_time
= tnow
;
951 last_io_operation
= "disk_space_avail";
952 if (disk_space_avail() < _free_space_min_avail
&& disk_space() > 0) {
953 DEV_PRINTF("Out of space for logging\n");
955 _open_error_ms
= AP_HAL::millis(); // prevent logging starting again for 5s
956 last_io_operation
= "";
959 last_io_operation
= "";
962 _last_write_time
= tnow
;
963 if (nbytes
> _writebuf_chunk
) {
964 // be kind to the filesystem layer
965 nbytes
= _writebuf_chunk
;
969 const uint8_t *head
= _writebuf
.readptr(size
);
970 nbytes
= MIN(nbytes
, size
);
972 #if !AP_FILESYSTEM_LITTLEFS_ENABLED
973 // try to align writes on a 512 byte boundary to avoid filesystem reads
974 if ((nbytes
+ _write_offset
) % 512 != 0) {
975 uint32_t ofs
= (nbytes
+ _write_offset
) % 512;
981 last_io_operation
= "write";
982 if (!write_fd_semaphore
.take(1)) {
985 if (_write_fd
== -1) {
986 write_fd_semaphore
.give();
990 #if AP_FILESYSTEM_LITTLEFS_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL
991 bool sync_block
= AP::littlefs().sync_block(_write_fd
, _write_offset
, nbytes
);
992 #endif // AP_FILESYSTEM_LITTLEFS_ENABLED
994 ssize_t nwritten
= AP::FS().write(_write_fd
, head
, nbytes
);
995 last_io_operation
= "";
997 if (errno
== ENOSPC
) {
998 DEV_PRINTF("Out of space for logging\n");
1000 _open_error_ms
= AP_HAL::millis(); // prevent logging starting again for 5s
1001 last_io_operation
= "";
1002 } else if ((tnow
- _last_write_ms
)/1000U > unsigned(_front
._params
.file_timeout
)) {
1003 // if we can't write for LOG_FILE_TIMEOUT seconds we give up and close
1004 // the file. This allows us to cope with temporary write
1005 // failures caused by directory listing
1006 last_io_operation
= "close";
1007 AP::FS().close(_write_fd
);
1008 last_io_operation
= "";
1010 printf("Failed to write to File: %s\n", strerror(errno
));
1012 _last_write_failed
= true;
1014 _last_write_failed
= false;
1015 _last_write_ms
= tnow
;
1016 _write_offset
+= nwritten
;
1017 _writebuf
.advance(nwritten
);
1020 fsync on littlefs is extremely expensive (20% CPU on an H7) particularly because the
1021 COW architecture can mean you end up copying a load of blocks. instead try and only sync
1022 at the end of a block to avoid copying and minimise CPU. fsync is needed for the file
1023 metadata (including size) to be updated
1025 #if CONFIG_HAL_BOARD != HAL_BOARD_SITL && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE
1026 #if AP_FILESYSTEM_LITTLEFS_ENABLED
1028 #endif // AP_FILESYSTEM_LITTLEFS_ENABLED
1031 the best strategy for minimizing corruption on microSD cards
1032 seems to be to write in 4k chunks and fsync the file on each
1033 chunk, ensuring the directory entry is updated after each
1036 last_io_operation
= "fsync";
1037 AP::FS().fsync(_write_fd
);
1038 last_io_operation
= "";
1042 #if AP_RTC_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
1043 // ChibiOS does not update mtime on writes, so if we opened
1044 // without knowing the time we should update it later
1045 if (_need_rtc_update
) {
1047 if (AP::rtc().get_utc_usec(utc_usec
)) {
1048 AP::FS().set_mtime(_write_filename
, utc_usec
/(1000U*1000U));
1049 _need_rtc_update
= false;
1055 write_fd_semaphore
.give();
1058 bool AP_Logger_File::io_thread_alive() const
1060 if (!hal
.scheduler
->is_system_initialized()) {
1061 // the system has long pauses during initialisation, assume still OK
1064 // if the io thread hasn't had a heartbeat in a while then it is
1065 #if CONFIG_HAL_BOARD == HAL_BOARD_ESP32
1066 uint32_t timeout_ms
= 10000;
1068 uint32_t timeout_ms
= 5000;
1070 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH)
1071 // the IO thread is working with hardware - writing to a physical
1072 // disk. Unfortunately these hardware devices do not obey our
1073 // SITL speedup options, so we allow for it here.
1074 SITL::SIM
*sitl
= AP::sitl();
1075 if (sitl
!= nullptr) {
1076 timeout_ms
*= sitl
->speedup
;
1079 return (AP_HAL::millis() - _io_timer_heartbeat
) < timeout_ms
;
1082 bool AP_Logger_File::logging_failed() const
1084 if (!_initialised
) {
1087 if (recent_open_error()) {
1090 if (!io_thread_alive()) {
1091 // No heartbeat in a second. IO thread is dead?! Very Not
1095 if (_last_write_failed
) {
1103 erase another file in async erase operation
1105 void AP_Logger_File::erase_next(void)
1107 char *fname
= _log_file_name(erase
.log_num
);
1108 if (fname
== nullptr) {
1113 AP::FS().unlink(fname
);
1117 if (erase
.log_num
<= _front
.get_max_num_logs()) {
1121 fname
= _lastlog_file_name();
1122 if (fname
!= nullptr) {
1123 AP::FS().unlink(fname
);
1127 _cached_oldest_log
= 0;
1132 #endif // HAL_LOGGING_FILESYSTEM_ENABLED