APM:Libraries
DataFlash_File.cpp
Go to the documentation of this file.
1 /*
2  DataFlash logging - file oriented variant
3 
4  This uses posix file IO to create log files called logs/NN.bin in the
5  given directory
6 
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
11  */
12 
13 #include <AP_HAL/AP_HAL.h>
14 
15 #if HAL_OS_POSIX_IO || HAL_OS_FATFS_IO
16 #include "DataFlash_File.h"
17 
18 #include <AP_Common/AP_Common.h>
19 
20 #if HAL_OS_POSIX_IO
21 #include <unistd.h>
22 #include <errno.h>
23 #include <stdlib.h>
24 #include <sys/types.h>
25 #include <sys/stat.h>
26 #include <fcntl.h>
27 #include <assert.h>
28 #include <stdio.h>
29 #include <time.h>
30 #include <dirent.h>
31 #if defined(__APPLE__) && defined(__MACH__)
32 #include <sys/param.h>
33 #include <sys/mount.h>
34 #else
35 #include <sys/statfs.h>
36 #endif
37 #endif
38 
39 #if HAL_OS_FATFS_IO
40 #include <stdio.h>
41 #endif
42 
43 #include <AP_Math/AP_Math.h>
44 #include <GCS_MAVLink/GCS.h>
45 
46 
47 extern const AP_HAL::HAL& hal;
48 
49 #define MAX_LOG_FILES 500U
50 #define DATAFLASH_PAGE_SIZE 1024UL
51 
52 /*
53  constructor
54  */
55 DataFlash_File::DataFlash_File(DataFlash_Class &front,
57  const char *log_directory) :
58  DataFlash_Backend(front, writer),
59  _write_fd(-1),
60  _read_fd(-1),
61  _log_directory(log_directory),
62  _writebuf(0),
63 #if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
64  // V1 gets IO errors with larger than 512 byte writes
65  _writebuf_chunk(512),
66 #elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V45)
67  _writebuf_chunk(512),
68 #elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V51)
69  _writebuf_chunk(512),
70 #elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V52)
71  _writebuf_chunk(512),
72 #elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V52E)
73  _writebuf_chunk(512),
74 #elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V51)
75  _writebuf_chunk(512),
76 #elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52)
77  _writebuf_chunk(512),
78 #elif defined(CONFIG_ARCH_BOARD_VRHERO_V10)
79  _writebuf_chunk(512),
80 #elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V54)
81  _writebuf_chunk(512),
82 #else
83  _writebuf_chunk(4096),
84 #endif
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"))
89 {
90  df_stats_clear();
91 }
92 
93 
94 void DataFlash_File::Init()
95 {
97  // create the log directory if need be
98  int ret;
99  struct stat st;
100 
101  semaphore = hal.util->new_semaphore();
102  if (semaphore == nullptr) {
103  AP_HAL::panic("Failed to create DataFlash_File semaphore");
104  return;
105  }
106  write_fd_semaphore = hal.util->new_semaphore();
107  if (write_fd_semaphore == nullptr) {
108  AP_HAL::panic("Failed to create DataFlash_File write_fd_semaphore");
109  return;
110  }
111 
112 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
113  // try to cope with an existing lowercase log directory
114  // name. NuttX does not handle case insensitive VFAT well
115  DIR *d = opendir("/fs/microsd/APM");
116  if (d != nullptr) {
117  for (struct dirent *de=readdir(d); de; de=readdir(d)) {
118  if (strcmp(de->d_name, "logs") == 0) {
119  rename("/fs/microsd/APM/logs", "/fs/microsd/APM/OLDLOGS");
120  break;
121  }
122  }
123  closedir(d);
124  }
125 #endif
126  const char* custom_dir = hal.util->get_custom_log_directory();
127  if (custom_dir != nullptr){
128  _log_directory = custom_dir;
129  }
130 
131  ret = stat(_log_directory, &st);
132  if (ret == -1) {
133  ret = mkdir(_log_directory, 0777);
134  }
135  if (ret == -1) {
136  printf("Failed to create log directory %s : %s\n", _log_directory, strerror(errno));
137  return;
138  }
139 
140  // determine and limit file backend buffersize
141  uint32_t bufsize = _front._params.file_bufsize;
142  if (bufsize > 64) {
143  bufsize = 64; // PixHawk has DMA limitations.
144  }
145  bufsize *= 1024;
146 
147  // If we can't allocate the full size, try to reduce it until we can allocate it
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);
150  bufsize >>= 1;
151  }
152 
153  if (!_writebuf.get_size()) {
154  hal.console->printf("Out of memory for logging\n");
155  return;
156  }
157 
158  hal.console->printf("DataFlash_File: buffer size=%u\n", (unsigned)bufsize);
159 
160  _initialised = true;
161  hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&DataFlash_File::_io_timer, void));
162 }
163 
164 bool DataFlash_File::file_exists(const char *filename) const
165 {
166  struct stat st;
167  if (stat(filename, &st) == -1) {
168  // hopefully errno==ENOENT. If some error occurs it is
169  // probably better to assume this file exists.
170  return false;
171  }
172  return true;
173 }
174 
175 bool DataFlash_File::log_exists(const uint16_t lognum) const
176 {
177  char *filename = _log_file_name(lognum);
178  if (filename == nullptr) {
179  return false; // ?!
180  }
181  bool ret = file_exists(filename);
182  free(filename);
183  return ret;
184 }
185 
186 void DataFlash_File::periodic_1Hz(const uint32_t now)
187 {
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);
191  }
192  if (io_thread_warning_decimation_counter++ > 57) {
193  io_thread_warning_decimation_counter = 0;
194  }
195  // If you try to close the file here then it will almost
196  // certainly block. Since this is the main thread, this is
197  // likely to cause a crash.
198 
199  // semaphore_write_fd not taken here as if the io thread is
200  // dead it may not release lock...
201  _write_fd = -1;
202  _initialised = false;
203  }
204  df_stats_log();
205 }
206 
207 void DataFlash_File::periodic_fullrate(const uint32_t now)
208 {
210 }
211 
212 uint32_t DataFlash_File::bufferspace_available()
213 {
214  const uint32_t space = _writebuf.space();
215  const uint32_t crit = critical_message_reserved_space();
216 
217  return (space > crit) ? space - crit : 0;
218 }
219 
220 // return true for CardInserted() if we successfully initialized
221 bool DataFlash_File::CardInserted(void) const
222 {
223  return _initialised && !_open_error;
224 }
225 
226 // returns the amount of disk space available in _log_directory (in bytes)
227 // returns -1 on error
228 int64_t DataFlash_File::disk_space_avail()
229 {
230 #if HAL_OS_POSIX_IO
231  struct statfs _stats;
232  if (statfs(_log_directory, &_stats) < 0) {
233  return -1;
234  }
235  return (((int64_t)_stats.f_bavail) * _stats.f_bsize);
236 #elif HAL_OS_FATFS_IO
237  return fs_getfree();
238 #else
239  // return a fake disk space size
240  return 100*1000*1000UL;
241 #endif
242 }
243 
244 // returns the total amount of disk space (in use + available) in
245 // _log_directory (in bytes).
246 // returns -1 on error
247 int64_t DataFlash_File::disk_space()
248 {
249 #if HAL_OS_POSIX_IO
250  struct statfs _stats;
251  if (statfs(_log_directory, &_stats) < 0) {
252  return -1;
253  }
254  return (((int64_t)_stats.f_blocks) * _stats.f_bsize);
255 #elif HAL_OS_FATFS_IO
256  return fs_gettotal();
257 #else
258  // return fake disk space size
259  return 200*1000*1000UL;
260 #endif
261 }
262 
263 // returns the available space in _log_directory as a percentage
264 // returns -1.0f on error
265 float DataFlash_File::avail_space_percent()
266 {
267  int64_t avail = disk_space_avail();
268  if (avail == -1) {
269  return -1.0f;
270  }
271  int64_t space = disk_space();
272  if (space == -1) {
273  return -1.0f;
274  }
275 
276  return (avail/(float)space) * 100;
277 }
278 
279 // find_oldest_log - find oldest log in _log_directory
280 // returns 0 if no log was found
281 uint16_t DataFlash_File::find_oldest_log()
282 {
283  if (_cached_oldest_log != 0) {
284  return _cached_oldest_log;
285  }
286 
287  uint16_t last_log_num = find_last_log();
288  if (last_log_num == 0) {
289  return 0;
290  }
291 
292  uint16_t current_oldest_log = 0; // 0 is invalid
293 
294  // We could count up to find_last_log(), but if people start
295  // relying on the min_avail_space_percent feature we could end up
296  // doing a *lot* of asprintf()s and stat()s
297  DIR *d = opendir(_log_directory);
298  if (d == nullptr) {
299  internal_error();
300  return 0;
301  }
302 
303  // we only remove files which look like xxx.BIN
304  for (struct dirent *de=readdir(d); de; de=readdir(d)) {
305  uint8_t length = strlen(de->d_name);
306  if (length < 5) {
307  // not long enough for \d+[.]BIN
308  continue;
309  }
310  if (strncmp(&de->d_name[length-4], ".BIN", 4)) {
311  // doesn't end in .BIN
312  continue;
313  }
314 
315  uint16_t thisnum = strtoul(de->d_name, nullptr, 10);
316  if (thisnum > MAX_LOG_FILES) {
317  // ignore files above our official maximum...
318  continue;
319  }
320  if (current_oldest_log == 0) {
321  current_oldest_log = thisnum;
322  } else {
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;
328  }
329  } else { // current_oldest_log > last_log_num
330  if (thisnum > last_log_num) {
331  if (thisnum < current_oldest_log) {
332  current_oldest_log = thisnum;
333  }
334  }
335  }
336  }
337  }
338  closedir(d);
339  _cached_oldest_log = current_oldest_log;
340 
341  return current_oldest_log;
342 }
343 
344 void DataFlash_File::Prep_MinSpace()
345 {
346  const uint16_t first_log_to_remove = find_oldest_log();
347  if (first_log_to_remove == 0) {
348  // no files to remove
349  return;
350  }
351 
352  _cached_oldest_log = 0;
353 
354  uint16_t log_to_remove = first_log_to_remove;
355 
356  uint16_t count = 0;
357  do {
358  float avail = avail_space_percent();
359  if (is_equal(avail, -1.0f)) {
360  internal_error();
361  break;
362  }
363  if (avail >= min_avail_space_percent) {
364  break;
365  }
366  if (count++ > MAX_LOG_FILES+10) {
367  // *way* too many deletions going on here. Possible internal error.
368  internal_error();
369  break;
370  }
371  char *filename_to_remove = _log_file_name(log_to_remove);
372  if (filename_to_remove == nullptr) {
373  internal_error();
374  break;
375  }
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) {
380  hal.console->printf("Failed to remove %s: %s\n", filename_to_remove, strerror(errno));
381  free(filename_to_remove);
382  if (errno == ENOENT) {
383  // corruption - should always have a continuous
384  // sequence of files... however, there may be still
385  // files out there, so keep going.
386  } else {
387  internal_error();
388  break;
389  }
390  } else {
391  free(filename_to_remove);
392  }
393  }
394  log_to_remove++;
395  if (log_to_remove > MAX_LOG_FILES) {
396  log_to_remove = 1;
397  }
398  } while (log_to_remove != first_log_to_remove);
399 }
400 
401 void DataFlash_File::Prep() {
402  if (!NeedPrep()) {
403  return;
404  }
405  if (hal.util->get_soft_armed()) {
406  // do not want to do any filesystem operations while we are e.g. flying
407  return;
408  }
409  Prep_MinSpace();
410 }
411 
412 bool DataFlash_File::NeedPrep()
413 {
414  if (!CardInserted()) {
415  // should not have been called?!
416  return false;
417  }
418 
419  if (avail_space_percent() < min_avail_space_percent) {
420  return true;
421  }
422 
423  return false;
424 }
425 
426 /*
427  construct a log file name given a log number.
428  The number in the log filename will *not* be zero-padded.
429  Note: Caller must free.
430  */
431 char *DataFlash_File::_log_file_name_short(const uint16_t log_num) const
432 {
433  char *buf = nullptr;
434  if (asprintf(&buf, "%s/%u.BIN", _log_directory, (unsigned)log_num) == -1) {
435  return nullptr;
436  }
437  return buf;
438 }
439 
440 /*
441  construct a log file name given a log number.
442  The number in the log filename will be zero-padded.
443  Note: Caller must free.
444  */
445 char *DataFlash_File::_log_file_name_long(const uint16_t log_num) const
446 {
447  char *buf = nullptr;
448  if (asprintf(&buf, "%s/%08u.BIN", _log_directory, (unsigned)log_num) == -1) {
449  return nullptr;
450  }
451  return buf;
452 }
453 
454 /*
455  return a log filename appropriate for the supplied log_num if a
456  filename exists with the short (not-zero-padded name) then it is the
457  appropirate name, otherwise the long (zero-padded) version is.
458  Note: Caller must free.
459  */
460 char *DataFlash_File::_log_file_name(const uint16_t log_num) const
461 {
462  char *filename = _log_file_name_short(log_num);
463  if (filename == nullptr) {
464  return nullptr;
465  }
466  if (file_exists(filename)) {
467  return filename;
468  }
469  free(filename);
470  return _log_file_name_long(log_num);
471 }
472 
473 /*
474  return path name of the lastlog.txt marker file
475  Note: Caller must free.
476  */
477 char *DataFlash_File::_lastlog_file_name(void) const
478 {
479  char *buf = nullptr;
480  if (asprintf(&buf, "%s/LASTLOG.TXT", _log_directory) == -1) {
481  return nullptr;
482  }
483  return buf;
484 }
485 
486 
487 // remove all log files
488 void DataFlash_File::EraseAll()
489 {
490  uint16_t log_num;
491  const bool was_logging = (_write_fd != -1);
492  stop_logging();
493 
494  for (log_num=1; log_num<=MAX_LOG_FILES; log_num++) {
495  char *fname = _log_file_name(log_num);
496  if (fname == nullptr) {
497  break;
498  }
499  unlink(fname);
500  free(fname);
501  }
502  char *fname = _lastlog_file_name();
503  if (fname != nullptr) {
504  unlink(fname);
505  free(fname);
506  }
507 
508  _cached_oldest_log = 0;
509 
510  if (was_logging) {
511  start_new_log();
512  }
513 }
514 
515 bool DataFlash_File::WritesOK() const
516 {
517  if (_write_fd == -1) {
518  return false;
519  }
520  if (_open_error) {
521  return false;
522  }
523  return true;
524 }
525 
526 
527 bool DataFlash_File::StartNewLogOK() const
528 {
529  if (_open_error) {
530  return false;
531  }
533 }
534 
535 /* Write a block of data at current offset */
536 bool DataFlash_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
537 {
539  _dropped++;
540  return false;
541  }
542 
543  if (!semaphore->take(1)) {
544  return false;
545  }
546 
547  uint32_t space = _writebuf.space();
548 
551  // the state machine has called us, and it has finished
552  // writing format messages out. It can always get back to us
553  // with more messages later, so let's leave room for other
554  // things:
555  if (space < non_messagewriter_message_reserved_space()) {
556  // this message isn't dropped, it will be sent again...
557  semaphore->give();
558  return false;
559  }
560  } else {
561  // we reserve some amount of space for critical messages:
562  if (!is_critical && space < critical_message_reserved_space()) {
563  _dropped++;
564  semaphore->give();
565  return false;
566  }
567  }
568 
569  // if no room for entire message - drop it:
570  if (space < size) {
571  hal.util->perf_count(_perf_overruns);
572  _dropped++;
573  semaphore->give();
574  return false;
575  }
576 
577  _writebuf.write((uint8_t*)pBuffer, size);
578  df_stats_gather(size);
579  semaphore->give();
580  return true;
581 }
582 
583 /*
584  read a packet. The header bytes have already been read.
585 */
586 bool DataFlash_File::ReadBlock(void *pkt, uint16_t size)
587 {
588  if (_read_fd == -1 || !_initialised || _open_error) {
589  return false;
590  }
591 
592  memset(pkt, 0, size);
593  if (::read(_read_fd, pkt, size) != size) {
594  return false;
595  }
596  _read_offset += size;
597  return true;
598 }
599 
600 
601 /*
602  find the highest log number
603  */
604 uint16_t DataFlash_File::find_last_log()
605 {
606  unsigned ret = 0;
607  char *fname = _lastlog_file_name();
608  if (fname == nullptr) {
609  return ret;
610  }
611  int fd = open(fname, O_RDONLY|O_CLOEXEC);
612  free(fname);
613  if (fd != -1) {
614  char buf[10];
615  memset(buf, 0, sizeof(buf));
616  if (read(fd, buf, sizeof(buf)-1) > 0) {
617 #if HAL_OS_POSIX_IO
618  sscanf(buf, "%u", &ret);
619 #else
620  ret = strtol(buf, NULL, 10);
621 #endif
622  }
623  close(fd);
624  }
625  return ret;
626 }
627 
628 uint32_t DataFlash_File::_get_log_size(const uint16_t log_num) const
629 {
630  char *fname = _log_file_name(log_num);
631  if (fname == nullptr) {
632  return 0;
633  }
634  struct stat st;
635  if (::stat(fname, &st) != 0) {
636  printf("Unable to fetch Log File Size: %s\n", strerror(errno));
637  free(fname);
638  return 0;
639  }
640  free(fname);
641  return st.st_size;
642 }
643 
644 uint32_t DataFlash_File::_get_log_time(const uint16_t log_num) const
645 {
646  char *fname = _log_file_name(log_num);
647  if (fname == nullptr) {
648  return 0;
649  }
650  struct stat st;
651  if (::stat(fname, &st) != 0) {
652  free(fname);
653  return 0;
654  }
655  free(fname);
656  return st.st_mtime;
657 }
658 
659 /*
660  convert a list entry number back into a log number (which can then
661  be converted into a filename). A "list entry number" is a sequence
662  where the oldest log has a number of 1, the second-from-oldest 2,
663  and so on. Thus the highest list entry number is equal to the
664  number of logs.
665 */
666 uint16_t DataFlash_File::_log_num_from_list_entry(const uint16_t list_entry)
667 {
668  uint16_t oldest_log = find_oldest_log();
669  if (oldest_log == 0) {
670  // We don't have any logs...
671  return 0;
672  }
673 
674  uint32_t log_num = oldest_log + list_entry - 1;
675  if (log_num > MAX_LOG_FILES) {
676  log_num -= MAX_LOG_FILES;
677  }
678  return (uint16_t)log_num;
679 }
680 
681 /*
682  find the number of pages in a log
683  */
684 void DataFlash_File::get_log_boundaries(const uint16_t list_entry, uint16_t & start_page, uint16_t & end_page)
685 {
686  const uint16_t log_num = _log_num_from_list_entry(list_entry);
687  if (log_num == 0) {
688  // that failed - probably no logs
689  start_page = 0;
690  end_page = 0;
691  return;
692  }
693 
694  start_page = 0;
695  end_page = _get_log_size(log_num) / DATAFLASH_PAGE_SIZE;
696 }
697 
698 /*
699  retrieve data from a log file
700  */
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)
702 {
703  if (!_initialised || _open_error) {
704  return -1;
705  }
706 
707  const uint16_t log_num = _log_num_from_list_entry(list_entry);
708  if (log_num == 0) {
709  // that failed - probably no logs
710  return -1;
711  }
712 
713  if (_read_fd != -1 && log_num != _read_fd_log_num) {
714  ::close(_read_fd);
715  _read_fd = -1;
716  }
717  if (_read_fd == -1) {
718  char *fname = _log_file_name(log_num);
719  if (fname == nullptr) {
720  return -1;
721  }
722  stop_logging();
723  _read_fd = ::open(fname, O_RDONLY|O_CLOEXEC);
724  if (_read_fd == -1) {
725  _open_error = true;
726  int saved_errno = errno;
727  ::printf("Log read open fail for %s - %s\n",
728  fname, strerror(saved_errno));
729  hal.console->printf("Log read open fail for %s - %s\n",
730  fname, strerror(saved_errno));
731  free(fname);
732  return -1;
733  }
734  free(fname);
735  _read_offset = 0;
736  _read_fd_log_num = log_num;
737  }
738  uint32_t ofs = page * (uint32_t)DATAFLASH_PAGE_SIZE + offset;
739 
740  /*
741  this rather strange bit of code is here to work around a bug
742  in file offsets in NuttX. Every few hundred blocks of reads
743  (starting at around 350k into a file) NuttX will get the
744  wrong offset for sequential reads. The offset it gets is
745  typically 128k earlier than it should be. It turns out that
746  calling lseek() with 0 offset and SEEK_CUR works around the
747  bug. We can remove this once we find the real bug.
748  */
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) {
752  close(_read_fd);
753  _read_fd = -1;
754  return -1;
755  }
756  if (seek_current != (off_t)_read_offset) {
757  if (::lseek(_read_fd, _read_offset, SEEK_SET) == (off_t)-1) {
758  close(_read_fd);
759  _read_fd = -1;
760  return -1;
761  }
762  }
763  }
764 
765  if (ofs != _read_offset) {
766  if (::lseek(_read_fd, ofs, SEEK_SET) == (off_t)-1) {
767  close(_read_fd);
768  _read_fd = -1;
769  return -1;
770  }
771  _read_offset = ofs;
772  }
773  int16_t ret = (int16_t)::read(_read_fd, data, len);
774  if (ret > 0) {
775  _read_offset += ret;
776  }
777  return ret;
778 }
779 
780 /*
781  find size and date of a log
782  */
783 void DataFlash_File::get_log_info(const uint16_t list_entry, uint32_t &size, uint32_t &time_utc)
784 {
785  uint16_t log_num = _log_num_from_list_entry(list_entry);
786  if (log_num == 0) {
787  // that failed - probably no logs
788  size = 0;
789  time_utc = 0;
790  return;
791  }
792 
793  size = _get_log_size(log_num);
794  time_utc = _get_log_time(log_num);
795 }
796 
797 
798 
799 /*
800  get the number of logs - note that the log numbers must be consecutive
801  */
802 uint16_t DataFlash_File::get_num_logs()
803 {
804  uint16_t ret = 0;
805  uint16_t high = find_last_log();
806  uint16_t i;
807  for (i=high; i>0; i--) {
808  if (! log_exists(i)) {
809  break;
810  }
811  ret++;
812  }
813  if (i == 0) {
814  for (i=MAX_LOG_FILES; i>high; i--) {
815  if (! log_exists(i)) {
816  break;
817  }
818  ret++;
819  }
820  }
821  return ret;
822 }
823 
824 /*
825  stop logging
826  */
827 void DataFlash_File::stop_logging(void)
828 {
829  // best-case effort to avoid annoying the IO thread
830  const bool have_sem = write_fd_semaphore->take(1);
831  if (_write_fd != -1) {
832  int fd = _write_fd;
833  _write_fd = -1;
834  ::close(fd);
835  }
836  if (have_sem) {
837  write_fd_semaphore->give();
838  } else {
840  }
841 }
842 
843 void DataFlash_File::PrepForArming()
844 {
845  if (logging_started()) {
846  return;
847  }
848  start_new_log();
849 }
850 
851 /*
852  start writing to a new log file
853  */
854 uint16_t DataFlash_File::start_new_log(void)
855 {
856  stop_logging();
857 
859 
860  if (_open_error) {
861  // we have previously failed to open a file - don't try again
862  // to prevent us trying to open files while in flight
863  return 0xFFFF;
864  }
865 
866  if (_read_fd != -1) {
867  ::close(_read_fd);
868  _read_fd = -1;
869  }
870 
871  if (disk_space_avail() < _free_space_min_avail) {
872  hal.console->printf("Out of space for logging\n");
873  _open_error = true;
874  return 0xffff;
875  }
876 
877  uint16_t log_num = find_last_log();
878  // re-use empty logs if possible
879  if (_get_log_size(log_num) > 0 || log_num == 0) {
880  log_num++;
881  }
882  if (log_num > MAX_LOG_FILES) {
883  log_num = 1;
884  }
885  char *fname = _log_file_name(log_num);
886  if (fname == nullptr) {
887  _open_error = true;
888  return 0xFFFF;
889  }
890  if (!write_fd_semaphore->take(1)) {
891  _open_error = true;
892  return 0xFFFF;
893  }
894 #if HAL_OS_POSIX_IO
895  _write_fd = ::open(fname, O_WRONLY|O_CREAT|O_TRUNC|O_CLOEXEC, 0666);
896 #else
897  //TODO add support for mode flags
898  _write_fd = ::open(fname, O_WRONLY|O_CREAT|O_TRUNC|O_CLOEXEC);
899 #endif
900  _cached_oldest_log = 0;
901 
902  if (_write_fd == -1) {
903  _initialised = false;
904  _open_error = true;
905  write_fd_semaphore->give();
906  int saved_errno = errno;
907  ::printf("Log open fail for %s - %s\n",
908  fname, strerror(saved_errno));
909  hal.console->printf("Log open fail for %s - %s\n",
910  fname, strerror(saved_errno));
911  free(fname);
912  return 0xFFFF;
913  }
914  free(fname);
915  _write_offset = 0;
916  _writebuf.clear();
917  write_fd_semaphore->give();
918 
919  // now update lastlog.txt with the new log number
920  fname = _lastlog_file_name();
921 
922  // we avoid fopen()/fprintf() here as it is not available on as many
923  // systems as open/write
924 #if HAL_OS_POSIX_IO
925  int fd = open(fname, O_WRONLY|O_CREAT|O_CLOEXEC, 0644);
926 #else
927  int fd = open(fname, O_WRONLY|O_CREAT|O_CLOEXEC);
928 #endif
929  free(fname);
930  if (fd == -1) {
931  _open_error = true;
932  return 0xFFFF;
933  }
934 
935  char buf[30];
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);
939  close(fd);
940 
941  if (written < to_write) {
942  _open_error = true;
943  return 0xFFFF;
944  }
945 
946  return log_num;
947 }
948 
949 
950 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
951 void DataFlash_File::flush(void)
952 {
953  uint32_t tnow = AP_HAL::millis();
955  while (_write_fd != -1 && _initialised && !_open_error && _writebuf.available()) {
956  // convince the IO timer that it really is OK to write out
957  // less than _writebuf_chunk bytes:
958  if (tnow > 2001) { // avoid resetting _last_write_time to 0
959  _last_write_time = tnow - 2001;
960  }
961  _io_timer();
962  }
964  if (write_fd_semaphore->take(1)) {
965  if (_write_fd != -1) {
966  ::fsync(_write_fd);
967  }
968  write_fd_semaphore->give();
969  } else {
971  }
972 }
973 #endif
974 
975 void DataFlash_File::_io_timer(void)
976 {
977  uint32_t tnow = AP_HAL::millis();
978  _io_timer_heartbeat = tnow;
979  if (_write_fd == -1 || !_initialised || _open_error) {
980  return;
981  }
982 
983  uint32_t nbytes = _writebuf.available();
984  if (nbytes == 0) {
985  return;
986  }
987  if (nbytes < _writebuf_chunk &&
988  tnow - _last_write_time < 2000UL) {
989  // write in _writebuf_chunk-sized chunks, but always write at
990  // least once per 2 seconds if data is available
991  return;
992  }
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) {
997  hal.console->printf("Out of space for logging\n");
998  stop_logging();
999  _open_error = true; // prevent logging starting again
1000  last_io_operation = "";
1001  return;
1002  }
1003  last_io_operation = "";
1004  }
1005 
1006  hal.util->perf_begin(_perf_write);
1007 
1008  _last_write_time = tnow;
1009  if (nbytes > _writebuf_chunk) {
1010  // be kind to the FAT PX4 filesystem
1011  nbytes = _writebuf_chunk;
1012  }
1013 
1014  uint32_t size;
1015  const uint8_t *head = _writebuf.readptr(size);
1016  nbytes = MIN(nbytes, size);
1017 
1018  // try to align writes on a 512 byte boundary to avoid filesystem reads
1019  if ((nbytes + _write_offset) % 512 != 0) {
1020  uint32_t ofs = (nbytes + _write_offset) % 512;
1021  if (ofs < nbytes) {
1022  nbytes -= ofs;
1023  }
1024  }
1025 
1026  last_io_operation = "write";
1027  if (!write_fd_semaphore->take(1)) {
1028  return;
1029  }
1030  if (_write_fd == -1) {
1031  write_fd_semaphore->give();
1032  return;
1033  }
1034  ssize_t nwritten = ::write(_write_fd, head, nbytes);
1035  last_io_operation = "";
1036  if (nwritten <= 0) {
1037  hal.util->perf_count(_perf_errors);
1038  last_io_operation = "close";
1039  close(_write_fd);
1040  last_io_operation = "";
1041  _write_fd = -1;
1042  _initialised = false;
1043  printf("Failed to write to File: %s\n", strerror(errno));
1044  } else {
1045  _write_offset += nwritten;
1046  _writebuf.advance(nwritten);
1047  /*
1048  the best strategy for minimizing corruption on microSD cards
1049  seems to be to write in 4k chunks and fsync the file on each
1050  chunk, ensuring the directory entry is updated after each
1051  write.
1052  */
1053 #if CONFIG_HAL_BOARD != HAL_BOARD_SITL && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE
1054  last_io_operation = "fsync";
1055  ::fsync(_write_fd);
1056  last_io_operation = "";
1057 #endif
1058  }
1059  write_fd_semaphore->give();
1060  hal.util->perf_end(_perf_write);
1061 }
1062 
1063 // this sensor is enabled if we should be logging at the moment
1064 bool DataFlash_File::logging_enabled() const
1065 {
1066  if (hal.util->get_soft_armed() ||
1068  return true;
1069  }
1070  return false;
1071 }
1072 
1073 bool DataFlash_File::io_thread_alive() const
1074 {
1075  // if the io thread hasn't had a heartbeat in a full second then it is dead
1076  return (AP_HAL::millis() - _io_timer_heartbeat) < 1000;
1077 }
1078 
1079 bool DataFlash_File::logging_failed() const
1080 {
1081  if (!_initialised) {
1082  return true;
1083  }
1084  if (_open_error) {
1085  return true;
1086  }
1087  if (!io_thread_alive()) {
1088  // No heartbeat in a second. IO thread is dead?! Very Not
1089  // Good.
1090  return true;
1091  }
1092 
1093  return false;
1094 }
1095 
1096 
1097 void DataFlash_File::vehicle_was_disarmed()
1098 {
1100  // rotate our log. Closing the current one and letting the
1101  // logging restart naturally based on log_disarmed should do
1102  // the trick:
1103  stop_logging();
1104  }
1105 }
1106 
1107 void DataFlash_File::Log_Write_DataFlash_Stats_File(const struct df_stats &_stats)
1108 {
1109  struct log_DSF pkt = {
1112  dropped : _dropped,
1114  blocks : _stats.blocks,
1115  bytes : _stats.bytes,
1116  buf_space_min : _stats.buf_space_min,
1117  buf_space_max : _stats.buf_space_max,
1118  buf_space_avg : (_stats.blocks) ? (_stats.buf_space_sigma / _stats.blocks) : 0,
1119 
1120  };
1121  WriteBlock(&pkt, sizeof(pkt));
1122 }
1123 
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;
1128  }
1129  if (space_remaining > stats.buf_space_max) {
1130  stats.buf_space_max = space_remaining;
1131  }
1132  stats.buf_space_sigma += space_remaining;
1133  stats.bytes += bytes_written;
1134  stats.blocks++;
1135 }
1136 
1137 void DataFlash_File::df_stats_clear() {
1138  memset(&stats, '\0', sizeof(stats));
1139  stats.buf_space_min = -1;
1140 }
1141 
1142 void DataFlash_File::df_stats_log() {
1143  Log_Write_DataFlash_Stats_File(stats);
1144  df_stats_clear();
1145 }
1146 
1147 
1148 #endif // HAL_OS_POSIX_IO
uint16_t blocks
Definition: LogStructure.h:154
int printf(const char *fmt,...)
Definition: stdio.c:113
bool get_soft_armed() const
Definition: Util.h:15
virtual void stop_logging(void)=0
int rename(const char *oldpath, const char *newpath)
POSIX rename a file by name.
Definition: posix.c:1648
uint32_t buf_space_min
Definition: LogStructure.h:156
DFMessageWriter_DFLogStart * _startup_messagewriter
int64_t fs_gettotal()
Definition: posix.c:1420
uint32_t buf_space_avg
Definition: LogStructure.h:158
dirent_t * readdir(DIR *dirp)
Definition: posix.c:1768
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
virtual bool CardInserted(void) const =0
virtual const char * get_custom_log_directory() const
Definition: Util.h:21
AP_HAL::UARTDriver * console
Definition: HAL.h:110
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.
Definition: posix.c:1852
uint8_t internal_errors
Definition: LogStructure.h:153
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
Definition: posix.c:1169
virtual void Init()
struct DataFlash_Class::@194 _params
AP_HAL::Util * util
Definition: HAL.h:115
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
GCS & gcs()
virtual Semaphore * new_semaphore(void)
Definition: Util.h:108
#define MIN(a, b)
Definition: usb_conf.h:215
int64_t fs_getfree()
Definition: posix.c:1405
virtual void resume_timer_procs()=0
Definition: ff.h:201
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
uint32_t bytes
Definition: LogStructure.h:155
virtual uint16_t find_last_log()=0
uint64_t time_us
Definition: LogStructure.h:151
virtual bool WriteBlockCheckStartupMessages()
#define f(i)
int sscanf(const char *buf, const char *fmt,...)
Definition: stdio.c:136
uint32_t millis()
Definition: system.cpp:157
bool log_while_disarmed(void) const
Definition: DataFlash.h:188
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
AP_Int8 file_bufsize
Definition: DataFlash.h:197
virtual void perf_end(perf_counter_t h)
Definition: Util.h:104
uint64_t micros64()
Definition: system.cpp:162
int unlink(const char *pathname)
POSIX delete a file.
Definition: posix.c:1693
off_t lseek(int fileno, off_t position, int whence)
POSIX seek to file position.
Definition: posix.c:612
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
int mkdir(const char *pathname, mode_t mode)
POSIX make a directory.
Definition: posix.c:1620
virtual void suspend_timer_procs()=0
#define NULL
Definition: hal_types.h:59
void free(void *ptr)
Definition: malloc.c:81
Common definitions and utility routines for the ArduPilot libraries.
DataFlash_Class & _front
int stat(const char *name, struct stat *buf)
Display struct stat, from POSIX stat(0 or fstat(), in ASCII. NOT POSIX.
Definition: posix.c:1319
static uint16_t log_num
virtual void register_io_process(AP_HAL::MemberProc)=0
int closedir(DIR *dirp)
POSIX closedir.
Definition: posix.c:1730
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)
Definition: AP_Math.cpp:12
virtual void perf_begin(perf_counter_t h)
Definition: Util.h:103
uint32_t buf_space_max
Definition: LogStructure.h:157
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
int snprintf(char *str, size_t size, const char *fmt,...)
Definition: stdio.c:64
int fsync(int fileno)
Definition: posix.c:2562
uint32_t dropped
Definition: LogStructure.h:152
int asprintf(char **strp, const char *fmt,...)
Definition: stdio.c:91
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
virtual uint16_t start_new_log(void)=0
DIR * opendir(const char *pathdir)
Definition: posix.c:1749
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
bool WriteBlock(const void *pBuffer, uint16_t size)
virtual bool NeedPrep()=0
#define LOG_PACKET_HEADER_INIT(id)
Definition: LogStructure.h:8
virtual void push_log_blocks()
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
virtual bool logging_started(void) const =0
virtual void perf_count(perf_counter_t h)
Definition: Util.h:105
AP_Int8 file_disarm_rot
Definition: DataFlash.h:198