15 #if HAL_OS_POSIX_IO || HAL_OS_FATFS_IO 24 #include <sys/types.h> 31 #if defined(__APPLE__) && defined(__MACH__) 32 #include <sys/param.h> 33 #include <sys/mount.h> 35 #include <sys/statfs.h> 49 #define MAX_LOG_FILES 500U 50 #define DATAFLASH_PAGE_SIZE 1024UL 57 const char *log_directory) :
61 _log_directory(log_directory),
63 #if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
66 #elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V45)
68 #elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V51)
70 #elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V52)
72 #elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V52E)
74 #elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V51)
76 #elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52)
78 #elif defined(CONFIG_ARCH_BOARD_VRHERO_V10)
80 #elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V54)
83 _writebuf_chunk(4096),
85 _perf_write(hal.util->perf_alloc(
AP_HAL::Util::PC_ELAPSED,
"DF_write")),
86 _perf_fsync(hal.util->perf_alloc(
AP_HAL::Util::PC_ELAPSED,
"DF_fsync")),
87 _perf_errors(hal.util->perf_alloc(
AP_HAL::Util::PC_COUNT,
"DF_errors")),
88 _perf_overruns(hal.util->perf_alloc(
AP_HAL::Util::PC_COUNT,
"DF_overruns"))
94 void DataFlash_File::Init()
102 if (semaphore ==
nullptr) {
107 if (write_fd_semaphore ==
nullptr) {
108 AP_HAL::panic(
"Failed to create DataFlash_File write_fd_semaphore");
112 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN 118 if (strcmp(de->d_name,
"logs") == 0) {
119 rename(
"/fs/microsd/APM/logs",
"/fs/microsd/APM/OLDLOGS");
127 if (custom_dir !=
nullptr){
128 _log_directory = custom_dir;
131 ret =
stat(_log_directory, &st);
133 ret =
mkdir(_log_directory, 0777);
148 while (!_writebuf.set_size(bufsize) && bufsize >= _writebuf_chunk) {
149 hal.
console->
printf(
"DataFlash_File: Couldn't set buffer size to=%u\n", (
unsigned)bufsize);
153 if (!_writebuf.get_size()) {
158 hal.
console->
printf(
"DataFlash_File: buffer size=%u\n", (
unsigned)bufsize);
164 bool DataFlash_File::file_exists(
const char *filename)
const 167 if (
stat(filename, &st) == -1) {
175 bool DataFlash_File::log_exists(
const uint16_t lognum)
const 177 char *filename = _log_file_name(lognum);
178 if (filename ==
nullptr) {
181 bool ret = file_exists(filename);
186 void DataFlash_File::periodic_1Hz(
const uint32_t now)
188 if (!io_thread_alive()) {
189 if (io_thread_warning_decimation_counter == 0) {
190 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"No IO Thread Heartbeat (%s)", last_io_operation);
192 if (io_thread_warning_decimation_counter++ > 57) {
193 io_thread_warning_decimation_counter = 0;
207 void DataFlash_File::periodic_fullrate(
const uint32_t now)
212 uint32_t DataFlash_File::bufferspace_available()
214 const uint32_t space = _writebuf.space();
215 const uint32_t crit = critical_message_reserved_space();
217 return (space > crit) ? space - crit : 0;
221 bool DataFlash_File::CardInserted(
void)
const 228 int64_t DataFlash_File::disk_space_avail()
231 struct statfs _stats;
232 if (statfs(_log_directory, &_stats) < 0) {
235 return (((int64_t)_stats.f_bavail) * _stats.f_bsize);
236 #elif HAL_OS_FATFS_IO 240 return 100*1000*1000UL;
247 int64_t DataFlash_File::disk_space()
250 struct statfs _stats;
251 if (statfs(_log_directory, &_stats) < 0) {
254 return (((int64_t)_stats.f_blocks) * _stats.f_bsize);
255 #elif HAL_OS_FATFS_IO 259 return 200*1000*1000UL;
265 float DataFlash_File::avail_space_percent()
267 int64_t avail = disk_space_avail();
271 int64_t space = disk_space();
276 return (avail/(
float)space) * 100;
281 uint16_t DataFlash_File::find_oldest_log()
283 if (_cached_oldest_log != 0) {
284 return _cached_oldest_log;
288 if (last_log_num == 0) {
292 uint16_t current_oldest_log = 0;
305 uint8_t length = strlen(de->d_name);
310 if (strncmp(&de->d_name[length-4],
".BIN", 4)) {
315 uint16_t thisnum = strtoul(de->d_name,
nullptr, 10);
316 if (thisnum > MAX_LOG_FILES) {
320 if (current_oldest_log == 0) {
321 current_oldest_log = thisnum;
323 if (current_oldest_log <= last_log_num) {
324 if (thisnum > last_log_num) {
325 current_oldest_log = thisnum;
326 }
else if (thisnum < current_oldest_log) {
327 current_oldest_log = thisnum;
330 if (thisnum > last_log_num) {
331 if (thisnum < current_oldest_log) {
332 current_oldest_log = thisnum;
339 _cached_oldest_log = current_oldest_log;
341 return current_oldest_log;
344 void DataFlash_File::Prep_MinSpace()
346 const uint16_t first_log_to_remove = find_oldest_log();
347 if (first_log_to_remove == 0) {
352 _cached_oldest_log = 0;
354 uint16_t log_to_remove = first_log_to_remove;
358 float avail = avail_space_percent();
363 if (avail >= min_avail_space_percent) {
366 if (count++ > MAX_LOG_FILES+10) {
371 char *filename_to_remove = _log_file_name(log_to_remove);
372 if (filename_to_remove ==
nullptr) {
376 if (file_exists(filename_to_remove)) {
377 hal.
console->
printf(
"Removing (%s) for minimum-space requirements (%.2f%% < %.0f%%)\n",
378 filename_to_remove, (
double)avail, (
double)min_avail_space_percent);
379 if (
unlink(filename_to_remove) == -1) {
381 free(filename_to_remove);
382 if (
errno == ENOENT) {
391 free(filename_to_remove);
395 if (log_to_remove > MAX_LOG_FILES) {
398 }
while (log_to_remove != first_log_to_remove);
401 void DataFlash_File::Prep() {
412 bool DataFlash_File::NeedPrep()
419 if (avail_space_percent() < min_avail_space_percent) {
431 char *DataFlash_File::_log_file_name_short(
const uint16_t
log_num)
const 434 if (
asprintf(&buf,
"%s/%u.BIN", _log_directory, (
unsigned)log_num) == -1) {
445 char *DataFlash_File::_log_file_name_long(
const uint16_t log_num)
const 448 if (
asprintf(&buf,
"%s/%08u.BIN", _log_directory, (
unsigned)log_num) == -1) {
460 char *DataFlash_File::_log_file_name(
const uint16_t log_num)
const 462 char *filename = _log_file_name_short(log_num);
463 if (filename ==
nullptr) {
466 if (file_exists(filename)) {
470 return _log_file_name_long(log_num);
477 char *DataFlash_File::_lastlog_file_name(
void)
const 480 if (
asprintf(&buf,
"%s/LASTLOG.TXT", _log_directory) == -1) {
488 void DataFlash_File::EraseAll()
491 const bool was_logging = (_write_fd != -1);
494 for (log_num=1; log_num<=MAX_LOG_FILES; log_num++) {
495 char *fname = _log_file_name(log_num);
496 if (fname ==
nullptr) {
502 char *fname = _lastlog_file_name();
503 if (fname !=
nullptr) {
508 _cached_oldest_log = 0;
515 bool DataFlash_File::WritesOK()
const 517 if (_write_fd == -1) {
527 bool DataFlash_File::StartNewLogOK()
const 536 bool DataFlash_File::_WritePrioritisedBlock(
const void *pBuffer, uint16_t size,
bool is_critical)
543 if (!semaphore->take(1)) {
547 uint32_t space = _writebuf.space();
555 if (space < non_messagewriter_message_reserved_space()) {
562 if (!is_critical && space < critical_message_reserved_space()) {
577 _writebuf.write((uint8_t*)pBuffer, size);
578 df_stats_gather(size);
586 bool DataFlash_File::ReadBlock(
void *pkt, uint16_t size)
592 memset(pkt, 0, size);
593 if (::
read(_read_fd, pkt, size) != size) {
596 _read_offset += size;
604 uint16_t DataFlash_File::find_last_log()
607 char *fname = _lastlog_file_name();
608 if (fname ==
nullptr) {
611 int fd =
open(fname, O_RDONLY|O_CLOEXEC);
615 memset(buf, 0,
sizeof(buf));
616 if (
read(fd, buf,
sizeof(buf)-1) > 0) {
620 ret = strtol(buf,
NULL, 10);
628 uint32_t DataFlash_File::_get_log_size(
const uint16_t log_num)
const 630 char *fname = _log_file_name(log_num);
631 if (fname ==
nullptr) {
635 if (::
stat(fname, &st) != 0) {
644 uint32_t DataFlash_File::_get_log_time(
const uint16_t log_num)
const 646 char *fname = _log_file_name(log_num);
647 if (fname ==
nullptr) {
651 if (::
stat(fname, &st) != 0) {
666 uint16_t DataFlash_File::_log_num_from_list_entry(
const uint16_t list_entry)
668 uint16_t oldest_log = find_oldest_log();
669 if (oldest_log == 0) {
674 uint32_t log_num = oldest_log + list_entry - 1;
675 if (log_num > MAX_LOG_FILES) {
676 log_num -= MAX_LOG_FILES;
684 void DataFlash_File::get_log_boundaries(
const uint16_t list_entry, uint16_t & start_page, uint16_t & end_page)
686 const uint16_t log_num = _log_num_from_list_entry(list_entry);
695 end_page = _get_log_size(log_num) / DATAFLASH_PAGE_SIZE;
701 int16_t DataFlash_File::get_log_data(
const uint16_t list_entry,
const uint16_t page,
const uint32_t offset,
const uint16_t len, uint8_t *data)
707 const uint16_t log_num = _log_num_from_list_entry(list_entry);
713 if (_read_fd != -1 && log_num != _read_fd_log_num) {
717 if (_read_fd == -1) {
718 char *fname = _log_file_name(log_num);
719 if (fname ==
nullptr) {
723 _read_fd =
::open(fname, O_RDONLY|O_CLOEXEC);
724 if (_read_fd == -1) {
726 int saved_errno =
errno;
727 ::printf(
"Log read open fail for %s - %s\n",
738 uint32_t ofs = page * (uint32_t)DATAFLASH_PAGE_SIZE + offset;
749 if (ofs / 4096 != (ofs+len) / 4096) {
750 off_t seek_current =
::lseek(_read_fd, 0, SEEK_CUR);
751 if (seek_current == (off_t)-1) {
756 if (seek_current != (off_t)_read_offset) {
757 if (::
lseek(_read_fd, _read_offset, SEEK_SET) == (off_t)-1) {
765 if (ofs != _read_offset) {
766 if (::
lseek(_read_fd, ofs, SEEK_SET) == (off_t)-1) {
773 int16_t ret = (int16_t)::
read(_read_fd, data, len);
783 void DataFlash_File::get_log_info(
const uint16_t list_entry, uint32_t &size, uint32_t &time_utc)
785 uint16_t log_num = _log_num_from_list_entry(list_entry);
793 size = _get_log_size(log_num);
794 time_utc = _get_log_time(log_num);
802 uint16_t DataFlash_File::get_num_logs()
807 for (i=high; i>0; i--) {
808 if (! log_exists(i)) {
814 for (i=MAX_LOG_FILES; i>high; i--) {
815 if (! log_exists(i)) {
827 void DataFlash_File::stop_logging(
void)
830 const bool have_sem = write_fd_semaphore->take(1);
831 if (_write_fd != -1) {
837 write_fd_semaphore->give();
843 void DataFlash_File::PrepForArming()
854 uint16_t DataFlash_File::start_new_log(
void)
866 if (_read_fd != -1) {
871 if (disk_space_avail() < _free_space_min_avail) {
879 if (_get_log_size(log_num) > 0 || log_num == 0) {
882 if (log_num > MAX_LOG_FILES) {
885 char *fname = _log_file_name(log_num);
886 if (fname ==
nullptr) {
890 if (!write_fd_semaphore->take(1)) {
895 _write_fd =
::open(fname, O_WRONLY|O_CREAT|O_TRUNC|O_CLOEXEC, 0666);
898 _write_fd =
::open(fname, O_WRONLY|O_CREAT|O_TRUNC|O_CLOEXEC);
900 _cached_oldest_log = 0;
902 if (_write_fd == -1) {
905 write_fd_semaphore->give();
906 int saved_errno =
errno;
907 ::printf(
"Log open fail for %s - %s\n",
917 write_fd_semaphore->give();
920 fname = _lastlog_file_name();
925 int fd =
open(fname, O_WRONLY|O_CREAT|O_CLOEXEC, 0644);
927 int fd =
open(fname, O_WRONLY|O_CREAT|O_CLOEXEC);
936 snprintf(buf,
sizeof(buf),
"%u\r\n", (
unsigned)log_num);
937 const ssize_t to_write = strlen(buf);
938 const ssize_t written =
write(fd, buf, to_write);
941 if (written < to_write) {
950 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX 951 void DataFlash_File::flush(
void)
955 while (_write_fd != -1 &&
_initialised && !_open_error && _writebuf.available()) {
959 _last_write_time = tnow - 2001;
964 if (write_fd_semaphore->take(1)) {
965 if (_write_fd != -1) {
968 write_fd_semaphore->give();
975 void DataFlash_File::_io_timer(
void)
978 _io_timer_heartbeat = tnow;
983 uint32_t nbytes = _writebuf.available();
987 if (nbytes < _writebuf_chunk &&
988 tnow - _last_write_time < 2000UL) {
993 if (tnow - _free_space_last_check_time > _free_space_check_interval) {
994 _free_space_last_check_time = tnow;
995 last_io_operation =
"disk_space_avail";
996 if (disk_space_avail() < _free_space_min_avail) {
1000 last_io_operation =
"";
1003 last_io_operation =
"";
1008 _last_write_time = tnow;
1009 if (nbytes > _writebuf_chunk) {
1011 nbytes = _writebuf_chunk;
1015 const uint8_t *head = _writebuf.readptr(size);
1016 nbytes =
MIN(nbytes, size);
1019 if ((nbytes + _write_offset) % 512 != 0) {
1020 uint32_t ofs = (nbytes + _write_offset) % 512;
1026 last_io_operation =
"write";
1027 if (!write_fd_semaphore->take(1)) {
1030 if (_write_fd == -1) {
1031 write_fd_semaphore->give();
1034 ssize_t nwritten =
::write(_write_fd, head, nbytes);
1035 last_io_operation =
"";
1036 if (nwritten <= 0) {
1038 last_io_operation =
"close";
1040 last_io_operation =
"";
1045 _write_offset += nwritten;
1046 _writebuf.advance(nwritten);
1053 #if CONFIG_HAL_BOARD != HAL_BOARD_SITL && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE 1054 last_io_operation =
"fsync";
1056 last_io_operation =
"";
1059 write_fd_semaphore->give();
1064 bool DataFlash_File::logging_enabled()
const 1073 bool DataFlash_File::io_thread_alive()
const 1079 bool DataFlash_File::logging_failed()
const 1087 if (!io_thread_alive()) {
1097 void DataFlash_File::vehicle_was_disarmed()
1107 void DataFlash_File::Log_Write_DataFlash_Stats_File(
const struct df_stats &_stats)
1115 bytes : _stats.bytes,
1118 buf_space_avg : (_stats.blocks) ? (_stats.buf_space_sigma / _stats.blocks) : 0,
1124 void DataFlash_File::df_stats_gather(
const uint16_t bytes_written) {
1125 const uint32_t space_remaining = _writebuf.space();
1126 if (space_remaining < stats.buf_space_min) {
1127 stats.buf_space_min = space_remaining;
1129 if (space_remaining > stats.buf_space_max) {
1130 stats.buf_space_max = space_remaining;
1132 stats.buf_space_sigma += space_remaining;
1133 stats.bytes += bytes_written;
1137 void DataFlash_File::df_stats_clear() {
1138 memset(&stats,
'\0',
sizeof(stats));
1139 stats.buf_space_min = -1;
1142 void DataFlash_File::df_stats_log() {
1143 Log_Write_DataFlash_Stats_File(stats);
1148 #endif // HAL_OS_POSIX_IO
int printf(const char *fmt,...)
bool get_soft_armed() const
virtual void stop_logging(void)=0
int rename(const char *oldpath, const char *newpath)
POSIX rename a file by name.
DFMessageWriter_DFLogStart * _startup_messagewriter
dirent_t * readdir(DIR *dirp)
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
virtual bool CardInserted(void) const =0
virtual const char * get_custom_log_directory() const
AP_HAL::UARTDriver * console
virtual bool StartNewLogOK() const
virtual void start_new_log_reset_variables()
Interface definition for the various Ground Control System.
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
struct DataFlash_Class::@194 _params
bool _writing_startup_messages
virtual Semaphore * new_semaphore(void)
virtual void resume_timer_procs()=0
virtual void printf(const char *,...) FMT_PRINTF(2
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
virtual uint16_t find_last_log()=0
virtual bool WriteBlockCheckStartupMessages()
int sscanf(const char *buf, const char *fmt,...)
bool log_while_disarmed(void) const
int close(int fileno)
POSIX Close a file with fileno handel.
virtual void perf_end(perf_counter_t h)
int unlink(const char *pathname)
POSIX delete a file.
off_t lseek(int fileno, off_t position, int whence)
POSIX seek to file position.
void send_text(MAV_SEVERITY severity, const char *fmt,...)
int mkdir(const char *pathname, mode_t mode)
POSIX make a directory.
virtual void suspend_timer_procs()=0
Common definitions and utility routines for the ArduPilot libraries.
int stat(const char *name, struct stat *buf)
Display struct stat, from POSIX stat(0 or fstat(), in ASCII. NOT POSIX.
virtual void register_io_process(AP_HAL::MemberProc)=0
int closedir(DIR *dirp)
POSIX closedir.
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
virtual void perf_begin(perf_counter_t h)
int errno
Note: fdevopen assigns stdin,stdout,stderr.
int snprintf(char *str, size_t size, const char *fmt,...)
int asprintf(char **strp, const char *fmt,...)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
virtual uint16_t start_new_log(void)=0
DIR * opendir(const char *pathdir)
void panic(const char *errormsg,...) FMT_PRINTF(1
bool WriteBlock(const void *pBuffer, uint16_t size)
virtual bool NeedPrep()=0
#define LOG_PACKET_HEADER_INIT(id)
virtual void push_log_blocks()
AP_HAL::Scheduler * scheduler
virtual bool logging_started(void) const =0
virtual void perf_count(perf_counter_t h)