APM:Libraries
DataFlash_File_sd.cpp
Go to the documentation of this file.
1 /*
2  DataFlash logging - file oriented variant
3 
4  This uses SD library to create log files called logs/NN.bin in the
5  given directory
6 
7  SD Card Rates
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 
14 #include <AP_HAL/AP_HAL.h>
15 
16 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT && (defined(BOARD_SDCARD_NAME) || defined(BOARD_DATAFLASH_FATFS))
17 
18 #include "DataFlash_File_sd.h"
19 
20 #include <AP_Common/AP_Common.h>
21 #include <assert.h>
22 #include <AP_Math/AP_Math.h>
23 #include <time.h>
24 #include <stdio.h>
25 #include <GCS_MAVLink/GCS.h>
27 
28 extern const AP_HAL::HAL& hal;
29 
30 #if defined(BOARD_DATAFLASH_FATFS)
31  #define MAX_LOG_FILES 9U
32 #else
33  #define MAX_LOG_FILES 50U
34 #endif
35 
36 #define DATAFLASH_PAGE_SIZE 1024UL
37 
38 #define MAX_FILE_SIZE 2048 * 1024L // not more 2MB
39 
40 /*
41  constructor
42  */
43 DataFlash_File::DataFlash_File(DataFlash_Class &front,
45  const char *log_directory) :
46  DataFlash_Backend(front, writer),
47  _write_fd(File()),
48  _read_fd(File()),
49  _log_directory(log_directory),
50  _writebuf(0),
51  _writebuf_chunk(4096)
52 {}
53 
54 
55 void DataFlash_File::Init()
56 {
58 
59  if(HAL_F4Light::state.sd_busy) return; // SD mounted via USB
60 
61  semaphore = hal.util->new_semaphore();
62  if (semaphore == nullptr) {
63  AP_HAL::panic("Failed to create DataFlash_File semaphore");
64  return;
65  }
66 
67 
68  // create the log directory if need be
69  const char* custom_dir = hal.util->get_custom_log_directory();
70  if (custom_dir != nullptr){
71  _log_directory = custom_dir;
72  }
73 
74  if (! SD.exists(_log_directory) ) {
75  char buf[80];
76  const char *cp, *rp;
77  char *wp;
78  for(cp=_log_directory + strlen(_log_directory);cp>_log_directory && *cp != '/';cp--){ }
79  for(wp=buf, rp=_log_directory; rp<cp;){
80  *wp++ = *rp++;
81  }
82  *wp++ = 0;
83  SD.mkdir(buf);
84 
85  if (!SD.mkdir(_log_directory)) {
86 
87  printf("Failed to create log directory %s: %s\n", _log_directory, SD.strError(SD.lastError));
88  gcs().send_text(MAV_SEVERITY_WARNING,"Failed to create log directory %s: %s", _log_directory, SD.strError(SD.lastError));
89  _log_directory="0:";
90  }
91  }
92 
93  // determine and limit file backend buffersize
94  uint32_t bufsize = _front._params.file_bufsize;
95  if (bufsize > 64) {
96  bufsize = 64; // DMA limitations.
97  }
98  bufsize *= 1024;
99 
100  // If we can't allocate the full size, try to reduce it until we can allocate it
101  while (!_writebuf.set_size(bufsize) && bufsize >= _writebuf_chunk) {
102  printf("DataFlash_File: Couldn't set buffer size to=%u\n", (unsigned)bufsize);
103  bufsize /= 2;
104  }
105 
106  if (!_writebuf.get_size()) {
107  printf("Out of memory for logging\n");
108  return;
109  }
110 
111  printf("DataFlash_File: buffer size=%u\n", (unsigned)bufsize);
112 
113  _initialised = true;
114  hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&DataFlash_File::_io_timer, void));
115 }
116 
117 bool DataFlash_File::file_exists(const char *filename) const
118 {
119  return SD.exists(filename);
120 }
121 
122 bool DataFlash_File::log_exists(const uint16_t lognum) const
123 {
124  char *filename = _log_file_name(lognum);
125  if (filename == nullptr) {
126  // internal_error();
127  return false; // ?!
128  }
129  bool ret = file_exists(filename);
130  free(filename);
131  return ret;
132 }
133 
134 void DataFlash_File::periodic_1Hz(const uint32_t now)
135 {
136  if (!(_write_fd) || !_initialised || _open_error || _busy) return; // too early
137 
138  if (!io_thread_alive()) {
139  gcs().send_text(MAV_SEVERITY_WARNING, "No IO Thread Heartbeat");
140  // If you try to close the file here then it will almost
141  // certainly block. Since this is the main thread, this is
142  // likely to cause a crash.
143 // _write_fd.close();
144  _write_fd.sync();
145  printf("\nLoging aborted\n");
146  _open_error = true;
147  _initialised = false;
148  }
149 }
150 
151 void DataFlash_File::periodic_fullrate(const uint32_t now)
152 {
154 }
155 
156 uint32_t DataFlash_File::bufferspace_available()
157 {
158  const uint32_t space = _writebuf.space();
159  const uint32_t crit = critical_message_reserved_space();
160 
161  return (space > crit) ? space - crit : 0;
162 }
163 
164 // return true for CardInserted() if we successfully initialized
165 bool DataFlash_File::CardInserted(void) const
166 {
167  return _initialised && !_open_error && !HAL_F4Light::state.sd_busy;
168 }
169 
170 // returns the available space in _log_directory as a percentage
171 // returns -1.0f on error
172 float DataFlash_File::avail_space_percent(uint32_t *free)
173 {
174 
175  uint32_t space;
176  int32_t avail = SD.getfree(_log_directory, &space);
177  if(free) *free = avail;
178  if (avail == -1) {
179  return -1.0f;
180  }
181 
182  return (avail/(float)space) * 100;
183 }
184 
185 #if 0 // why such hard?
186 
187 // find_oldest_log - find oldest log in _log_directory
188 // returns 0 if no log was found
189 uint16_t DataFlash_File::find_oldest_log()
190 {
191  if (_cached_oldest_log != 0) {
192  return _cached_oldest_log;
193  }
194 
195  uint16_t last_log_num = find_last_log();
196  if (last_log_num == 0) {
197  return 0;
198  }
199 
200  uint16_t current_oldest_log = 0; // 0 is invalid
201 
202  // We could count up to find_last_log(), but if people start
203  // relying on the min_avail_space_percent feature we could end up
204  // doing a *lot* of asprintf()s and stat()s
205  File dir = SD.open(_log_directory);
206  if (!dir) {
207  // internal_error();
208  printf("error opening logs dir: %s", SD.strError(SD.lastError));
209  return 0;
210  }
211 
212  // we only count files which look like xxx.BIN
213  while(1){
214  File de=dir.openNextFile();
215  if(!de) {
216  if(SD.lastError){
217  printf("error scanning logs: %s", SD.strError(SD.lastError));
218  }
219  break;
220  }
221 
222  char *nm = de.name();
223  de.close();
224 
225  uint8_t length = strlen(nm);
226  if (length < 5) {
227  // not long enough for \d+[.]BIN
228  continue;
229  }
230  if (strncmp(&nm[length-4], ".BIN", 4)) {
231  // doesn't end in .BIN
232  continue;
233  }
234 
235  uint16_t thisnum = strtoul(nm, nullptr, 10);
236  if (current_oldest_log == 0) {
237  current_oldest_log = thisnum;
238  } else {
239  if (current_oldest_log <= last_log_num) {
240  if (thisnum > last_log_num) {
241  current_oldest_log = thisnum;
242  } else if (thisnum < current_oldest_log) {
243  current_oldest_log = thisnum;
244  }
245  } else { // current_oldest_log > last_log_num
246  if (thisnum > last_log_num) {
247  if (thisnum < current_oldest_log) {
248  current_oldest_log = thisnum;
249  }
250  }
251  }
252  }
253  }
254  dir.close();
255  _cached_oldest_log = current_oldest_log;
256 
257  return current_oldest_log;
258 }
259 
260 #else
261 
262 // result cached later
263 uint16_t DataFlash_File::find_oldest_log()
264 {
265 
266  if (_cached_oldest_log != 0) {
267  return _cached_oldest_log;
268  }
269 
270  uint16_t i;
271  if(_last_oldest_log >=MAX_LOG_FILES-1) _last_oldest_log=1;
272  for (i=_last_oldest_log; i<MAX_LOG_FILES; i++) {
273  if ( log_exists(i)) {
274  _cached_oldest_log=i;
275  return i;
276  }
277  }
278 
279  return 0;
280 }
281 #endif
282 
283 
284 void DataFlash_File::Prep_MinSpace()
285 {
286  const uint16_t first_log_to_remove = find_oldest_log();
287  if (first_log_to_remove != 0) {
288 
289  _last_oldest_log = _cached_oldest_log + 1;
290  _cached_oldest_log = 0;
291 
292  uint16_t log_to_remove = first_log_to_remove;
293 
294  uint16_t count = 0;
295  do {
296  uint32_t free_sp;
297  float avail = avail_space_percent(&free_sp);
298 
299  if (avail < 0) { // internal_error()
300 #if defined(BOARD_DATAFLASH_FATFS)
301  printf("error getting free space, formatting!\n");
302  SD.format(_log_directory);
303  return;
304 #elif defined(BOARD_SDCARD_CS_PIN)
305  if(hal_param_helper->_sd_format){
306  printf("error getting free space, formatting!\n");
307  gcs().send_text(MAV_SEVERITY_WARNING,"error getting free space, formatting!");
308  SD.format(_log_directory);
309  return;
310  }
311 #endif
312  break;
313  }
314  if (avail >= min_avail_space_percent && free_sp*512 >= MAX_FILE_SIZE) { // not less 2MB - space for one file
315  break;
316  }
317  if (count++ > MAX_LOG_FILES+10) {
318  // *way* too many deletions going on here. Possible internal error.
319  break;
320  }
321  char *filename_to_remove = _log_file_name(log_to_remove);
322  if (filename_to_remove == nullptr) {
323  break;
324  }
325  if (SD.exists(filename_to_remove)) {
326  printf("Removing (%s) for minimum-space requirements (%.2f%% < %.0f%%) %.1fMb\n",
327  filename_to_remove, (double)avail, (double)min_avail_space_percent, free_sp/(1024.*2));
328  if (!SD.remove(filename_to_remove)) {
329  printf("Failed to remove %s: %s\n", filename_to_remove, SD.strError(SD.lastError));
330  }
331  free(filename_to_remove);
332  }
333  log_to_remove++;
334  if (log_to_remove > MAX_LOG_FILES) {
335  log_to_remove = 1;
336  }
337  } while (log_to_remove != first_log_to_remove);
338 
339  }
340 // check the result
341 #if defined(BOARD_DATAFLASH_FATFS)
342  float avail = avail_space_percent();
343  if (avail <= 0) { // erase don't helps
344  printf("erase don't get free space, formatting!\n");
345  SD.format(_log_directory);
346  }
347 #endif
348 
349 }
350 
351 
352 void DataFlash_File::Prep() {
353  if (hal.util->get_soft_armed()) {
354  // do not want to do any filesystem operations while we are e.g. flying
355  return;
356  }
357  Prep_MinSpace();
358 }
359 
360 bool DataFlash_File::NeedPrep()
361 {
362  if (!CardInserted()) {
363  // should not have been called?!
364  return false;
365  }
366 
367  if (avail_space_percent() < min_avail_space_percent) {
368  return true;
369  }
370 
371  return false;
372 }
373 
374 /*
375  construct a log file name given a log number.
376  Note: Caller must free.
377  */
378 char *DataFlash_File::_log_file_name(const uint16_t log_num) const
379 {
380  char *buf = (char *)malloc(256);
381  if(!buf) return nullptr;
382 
383  sprintf(buf, "%s/%u.BIN", _log_directory, (unsigned)log_num);
384 
385  return buf;
386 }
387 
388 /*
389  return path name of the lastlog.txt marker file
390  Note: Caller must free.
391  */
392 char *DataFlash_File::_lastlog_file_name(void) const
393 {
394  char *buf = (char *)malloc(256);
395  if(!buf) return nullptr;
396 
397  sprintf(buf, "%s/LASTLOG.TXT", _log_directory);
398  return buf;
399 }
400 
401 
402 // remove all log files
403 void DataFlash_File::EraseAll()
404 {
405  uint16_t log_num;
406  const bool was_logging = (_write_fd != -1);
407  stop_logging();
408 
409  for (log_num=1; log_num<=MAX_LOG_FILES; log_num++) {
410  char *fname = _log_file_name(log_num);
411  if (fname == nullptr) {
412  break;
413  }
414  SD.remove(fname);
415  free(fname);
416  }
417  char *fname = _lastlog_file_name();
418  if (fname != nullptr) {
419  SD.remove(fname);
420  free(fname);
421  }
422 
423  _cached_oldest_log = 0;
424 
425  if (was_logging) {
426  start_new_log();
427  }
428 }
429 
430 
431 bool DataFlash_File::WritesOK() const
432 {
433  if (!_write_fd) {
434  return false;
435  }
436  if (_open_error) {
437  return false;
438  }
439  return true;
440 }
441 
442 
443 bool DataFlash_File::StartNewLogOK() const
444 {
445  if (_open_error) {
446  return false;
447  }
449 }
450 
451 
452 /* Write a block of data at current offset */
453 bool DataFlash_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
454 {
456  _dropped++;
457  return false;
458  }
459 
460  if (!semaphore->take(1)) {
461  return false;
462  }
463 
464  uint32_t space = _writebuf.space();
465 
468  // the state machine has called us, and it has finished
469  // writing format messages out. It can always get back to us
470  // with more messages later, so let's leave room for other
471  // things:
472  if (space < non_messagewriter_message_reserved_space()) {
473  // this message isn't dropped, it will be sent again...
474  semaphore->give();
475  return false;
476  }
477  } else {
478  // we reserve some amount of space for critical messages:
479  if (!is_critical && space < critical_message_reserved_space()) {
480 // printf("dropping NC block! size=%d\n", size);
481  _dropped++;
482  semaphore->give();
483  return false;
484  }
485  }
486 
487  // if no room for entire message - drop it:
488  if (space < size) {
489 // hal.util->perf_count(_perf_overruns);
490  printf("dropping block! size=%d\n", size);
491 
492  _dropped++;
493  semaphore->give();
494  return false;
495  }
496 
497  _writebuf.write((uint8_t*)pBuffer, size);
498  has_data=true;
499 
500  semaphore->give();
501  return true;
502 }
503 
504 /*
505  read a packet. The header bytes have already been read.
506 */
507 bool DataFlash_File::ReadBlock(void *pkt, uint16_t size)
508 {
509  if (!(_read_fd) || !_initialised || _open_error) {
510  return false;
511  }
512 
513  memset(pkt, 0, size);
514  if (_read_fd.read(pkt, size) != size) {
515  return false;
516  }
517  _read_offset += size;
518  return true;
519 }
520 
521 
522 /*
523  find the highest log number
524  */
525 uint16_t DataFlash_File::find_last_log()
526 {
527  unsigned ret = 0;
528  char *fname = _lastlog_file_name();
529  if (fname == nullptr) {
530  return ret;
531  }
532  File fd = SD.open(fname, FILE_READ);
533  free(fname);
534  if (fd) {
535  char buf[10];
536  memset(buf, 0, sizeof(buf));
537  if (fd.read(buf, sizeof(buf)-1) > 0) {
538  ret = strtoul(buf, nullptr, 10); // зачем тащить толстую функцию зря
539 // sscanf(buf, "%u", &ret);
540  }
541  fd.close();
542  }
543  return ret;
544 }
545 
546 uint32_t DataFlash_File::_get_log_size(const uint16_t log_num) const
547 {
548  char *fname = _log_file_name(log_num);
549  if (fname == nullptr) {
550  return 0;
551  }
552 
553  File fd = SD.open(fname, FILE_READ);
554  free(fname);
555 
556  if(!fd) return 0;
557 
558  uint32_t sz= fd.size();
559  fd.close();
560 
561  return sz;
562 }
563 
564 uint32_t DataFlash_File::_get_log_time(const uint16_t log_num) const
565 {
566  char *fname = _log_file_name(log_num);
567  if (fname == nullptr) {
568  return 0;
569  }
570 
571  FILINFO fno;
572 
573  int8_t ret = SD.stat(fname, &fno);
574  free(fname);
575 
576  if(ret<0) return 0;
577 
578  uint16_t date=fno.fdate,
579  time=fno.ftime;
580 
581 
582  struct tm t;
583 
584  t.tm_sec = FAT_SECOND(time); // seconds after the minute 0-61*
585  t.tm_min = FAT_MINUTE(time); // minutes after the hour 0-59
586  t.tm_hour = FAT_HOUR(time); // hours since midnight 0-23
587  t.tm_mday = FAT_DAY(date); // day of the month 1-31
588  t.tm_mon = FAT_MONTH(date); // months since January 0-11
589  t.tm_year = FAT_YEAR(date); // years since 1900
590 // t.tm_yday int days since January 1 0-365
591  t.tm_isdst =false;
592 
593 
594  return to_timestamp(&t);
595 }
596 
597 /*
598  convert a list entry number back into a log number (which can then
599  be converted into a filename). A "list entry number" is a sequence
600  where the oldest log has a number of 1, the second-from-oldest 2,
601  and so on. Thus the highest list entry number is equal to the
602  number of logs.
603 */
604 uint16_t DataFlash_File::_log_num_from_list_entry(const uint16_t list_entry)
605 {
606  uint16_t oldest_log = find_oldest_log();
607  if (oldest_log == 0) {
608  // We don't have any logs...
609  return 0;
610  }
611 
612  uint32_t log_num = oldest_log + list_entry - 1;
613 
614  if (log_num > MAX_LOG_FILES) {
615  log_num -= MAX_LOG_FILES;
616  }
617  while(!log_exists(log_num)){ // skip gaps
618  log_num++;
619  if(log_num>MAX_LOG_FILES) {
620  log_num=MAX_LOG_FILES;
621  break;
622  }
623  }
624 
625  return (uint16_t)log_num;
626 }
627 
628 /*
629  find the number of pages in a log
630  */
631 void DataFlash_File::get_log_boundaries(const uint16_t list_entry, uint16_t & start_page, uint16_t & end_page)
632 {
633  const uint16_t log_num = _log_num_from_list_entry(list_entry);
634  //if (log_num == 0) {
635  if (! log_exists(log_num)) {
636  // that failed - probably no logs
637  start_page = 0;
638  end_page = 0;
639  return;
640  }
641 
642  start_page = 0;
643  end_page = _get_log_size(log_num) / DATAFLASH_PAGE_SIZE;
644 }
645 
646 /*
647  retrieve data from a log file
648  */
649 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)
650 {
651  if (!_initialised || _open_error) {
652  return -1;
653  }
654 
655  const uint16_t log_num = _log_num_from_list_entry(list_entry);
656  if (log_num == 0) {
657  // that failed - probably no logs
658  return -1;
659  }
660 
661  if (_read_fd && log_num != _read_fd_log_num) {
662  _read_fd.close();
663  }
664  if (!(_read_fd)) {
665  char *fname = _log_file_name(log_num);
666  if (fname == nullptr) {
667  return -1;
668  }
669  stop_logging();
670  _read_fd = SD.open(fname, O_RDONLY);
671  if (!(_read_fd)) {
672  _open_error = true;
673 
674  printf("Log read open fail for %s: %s\n", fname, SD.strError(SD.lastError));
675  free(fname);
676  return -1;
677  }
678  free(fname);
679  _read_offset = 0;
680  _read_fd_log_num = log_num;
681  }
682 
683  int16_t ret = (int16_t)_read_fd.read(data, len);
684  if (ret > 0) {
685  _read_offset += ret;
686  }
687  return ret;
688 }
689 
690 /*
691  find size and date of a log
692  */
693 void DataFlash_File::get_log_info(const uint16_t list_entry, uint32_t &size, uint32_t &time_utc)
694 {
695  uint16_t log_num = _log_num_from_list_entry(list_entry);
696 // if (log_num == 0) {
697  if (! log_exists(log_num)) {
698 
699  // that failed - probably no logs
700  size = 0;
701  time_utc = 0;
702  return;
703  }
704 
705  size = _get_log_size(log_num);
706  time_utc = _get_log_time(log_num);
707 }
708 
709 
710 
711 /*
712  get the number of logs [no more - note that the log numbers must be consecutive ]
713  */
714 uint16_t DataFlash_File::get_num_logs()
715 {
716  uint16_t ret = 0;
717  uint16_t high = find_last_log();
718  uint16_t i;
719  for (i=high; i>0; i--) {
720  if (log_exists(i)) {
721  ret++;
722  if(_cached_oldest_log == 0 || i<_cached_oldest_log)
723  _cached_oldest_log=i;
724  }
725  }
726 
727  if (i == 0) {
728  for (i=MAX_LOG_FILES; i>high; i--) {
729  if ( log_exists(i)) {
730  ret++;
731  if(_cached_oldest_log == 0 || i<_cached_oldest_log)
732  _cached_oldest_log=i;
733  }
734  }
735  }
736  return ret;
737 }
738 
739 /*
740  stop logging
741  */
742 void DataFlash_File::stop_logging(void)
743 {
744  if (_write_fd) {
745  _write_fd.close();
746  }
747 }
748 
749 
750 void DataFlash_File::PrepForArming()
751 {
752  if (logging_started()) {
753  return;
754  }
755  start_new_log();
756 }
757 
758 /*
759  start writing to a new log file
760  */
761 uint16_t DataFlash_File::start_new_log(void)
762 {
763  stop_logging();
764 
766 
767  if (_open_error) {
768  // we have previously failed to open a file - don't try again
769  // to prevent us trying to open files while in flight
770  return 0xFFFF;
771  }
772 
773  if (_read_fd) {
774  _read_fd.close();
775  }
776 
777  uint16_t log_num = find_last_log();
778  // re-use empty logs if possible
779  if (_get_log_size(log_num) > 0 || log_num == 0) {
780  log_num++;
781  }
782  if (log_num > MAX_LOG_FILES) {
783  log_num = 1;
784  }
785  _cached_oldest_log = 0;
786 
787  bool was_ovf=false;
788 
789  char *fname;
790  while(1) { // try to create log file
791 
792  fname = _log_file_name(log_num);
793  if (fname == nullptr) {
794  _open_error = true;
795  return 0xFFFF; // no memory
796  }
797 
798  _write_fd = SD.open(fname, O_WRITE|O_CREAT|O_TRUNC);
799 
800  if (_write_fd) { // file opened
801  free(fname);
802  break;
803  }
804 
805  // opening failed
806  printf("Log open fail for %s: %s\n",fname, SD.strError(SD.lastError));
807  free(fname);
808  if(SD.lastError == FR_DISK_ERR) {
809  _initialised = false; // no space
810  _open_error = true; // don't try any more
811  printf("\nLoging aborted\n");
812  return 0xFFFF;
813  }
814 
815  log_num++; // if not at end - try to open next log
816 
817  if (log_num >= MAX_LOG_FILES) {
818  log_num = 1;
819  if(was_ovf) {
820  _initialised = false; // no space
821  _open_error = true; // don't try any more
822  printf("\nLoging stopped\n");
823  return 0xFFFF;
824  }
825  was_ovf=true;
826  }
827  }
828  _write_offset = 0;
829  _writebuf.clear();
830  has_data = false;
831 
832  // now update lastlog.txt with the new log number
833  fname = _lastlog_file_name();
834 
835  File fd = SD.open(fname, O_WRITE|O_CREAT);
836  free(fname);
837  if (!fd) {
838  return 0xFFFF;
839  }
840 
841  char buf[30];
842  snprintf(buf, sizeof(buf), "%u\r\n", (unsigned)log_num);
843  const ssize_t to_write = strlen(buf);
844  const ssize_t written = fd.write((uint8_t *)buf, to_write);
845  fd.close();
846 
847  if (written < to_write) {
848  return 0xFFFF;
849  }
850 
851  return log_num;
852 }
853 
854 void DataFlash_File::_io_timer(void)
855 {
856  uint32_t tnow = AP_HAL::millis();
857  _io_timer_heartbeat = tnow;
858 
859  if (!(_write_fd) || !_initialised || _open_error || !has_data) {
860  return;
861  }
862 
863  uint32_t nbytes = _writebuf.available();
864  if (nbytes == 0) {
865  return;
866  }
867  if (nbytes < _writebuf_chunk &&
868  tnow - _last_write_time < 2000UL) {
869  // write in _writebuf_chunk-sized chunks, but always write at
870  // least once per 2 seconds if data is available
871  has_data=false;
872  return;
873  }
874 
875  _last_write_time = tnow;
876  if (nbytes > _writebuf_chunk) {
877  // be kind to the FAT filesystem
878  nbytes = _writebuf_chunk;
879  }
880 
881  uint32_t size;
882  const uint8_t *head = _writebuf.readptr(size);
883  nbytes = MIN(nbytes, size);
884 
885  // try to align writes on a 512 byte boundary to avoid filesystem reads
886  if ((nbytes + _write_offset) % 512 != 0) {
887  uint32_t ofs = (nbytes + _write_offset) % 512;
888  if (ofs < nbytes) {
889  nbytes -= ofs;
890  }
891  }
892 
893  if(nbytes==0) return;
894 
895  ssize_t nwritten = _write_fd.write(head, nbytes);
896  if (nwritten <= 0) {
897  FRESULT err=SD.lastError;
898  printf("\nLog write %ld bytes fails: %s\n",nbytes, SD.strError(err));
899  gcs().send_text(MAV_SEVERITY_WARNING,"Log write %ld bytes fails: %s",nbytes, SD.strError(err));
900 // stop_logging();
901  _write_fd.close();
902 #if defined(BOARD_DATAFLASH_FATFS)
903  if(FR_INT_ERR == err || FR_NO_FILESYSTEM == err) { // internal error - bad filesystem
904  gcs().send_text(MAV_SEVERITY_INFO, "Formatting DataFlash, please wait");
905  uint32_t t=AP_HAL::millis();
906  _busy = true; // format requires a long time and 1s task will kill process
907  SD.format(_log_directory);
908  _busy = false;
909  gcs().send_text(MAV_SEVERITY_INFO, "Formatting complete in %ldms", AP_HAL::millis() - t);
910  start_new_log(); // re-open logging
911  if(_write_fd) { // success?
912  nwritten = _write_fd.write(head, nbytes); // ok, try to write again
913  if(nwritten>0) { // if ok
914  _write_offset += nwritten; // then mark data as written
915  _writebuf.advance(nwritten);
916  _write_fd.sync(); // and fix it on SD
917  return;
918  }
919  }
920  } else
921 #else
922  if(FR_INT_ERR == err || FR_NO_FILESYSTEM == err || FR_INVALID_OBJECT == err) { // internal error - bad filesystem
923  gcs().send_text(MAV_SEVERITY_INFO, "logging cancelled");
924  _initialised = false;
925  _open_error = true;
926  } else
927 
928 #endif
929  {
930  _busy = true; // Prep_MinSpace requires a long time and 1s task will kill process
931  Prep_MinSpace();
932  _busy = false;
933  start_new_log(); // re-open logging
934  if(_write_fd) { // success?
935  nwritten = _write_fd.write(head, nbytes); // ok, try to write again
936  if(nwritten>0) { // if ok
937  _write_offset += nwritten; // then mark data as written
938  _writebuf.advance(nwritten);
939  _write_fd.sync(); // and fix it on SD
940  return;
941  }
942  }
943  }
944 
945  _initialised = false;
946  } else {
947  _write_offset += nwritten;
948  _writebuf.advance(nwritten);
949  /*
950  the best strategy for minimizing corruption on microSD cards
951  seems to be to write in 4k chunks and fsync the file on each
952  chunk, ensuring the directory entry is updated after each
953  write.
954  */
955  _write_fd.sync();
956 
957 #if defined(BOARD_DATAFLASH_FATFS) // limit file size in some MBytes and reopen new log file
958 
959  if(_write_fd.size() >= MAX_FILE_SIZE) { // size > 2M
960  stop_logging();
961  uint32_t t = AP_HAL::millis();
962  _busy = true;
963  Prep_MinSpace();
964  _busy = false;
965  printf("\nlog file reopened in %ldms\n", AP_HAL::millis() - t);
966  start_new_log(); // re-start logging
967  }
968 #endif
969  }
970 }
971 
972 // this sensor is enabled if we should be logging at the moment
973 bool DataFlash_File::logging_enabled() const
974 {
975  if (hal.util->get_soft_armed() ||
977  return true;
978  }
979  return false;
980 }
981 
982 bool DataFlash_File::io_thread_alive() const
983 {
984  uint32_t tnow = AP_HAL::millis();
985  // if the io thread hasn't had a heartbeat in a 5 second then it is dead
986  if(_io_timer_heartbeat + 5000 > tnow) return true;
987 
988  return false;
989 }
990 
991 bool DataFlash_File::logging_failed() const
992 {
993  bool op=false;
994 
995  if(_write_fd) op=true;
996 
997  if (!op &&
998  (hal.util->get_soft_armed() ||
1000  return true;
1001  }
1002  if (_open_error) {
1003  return true;
1004  }
1005  if (!io_thread_alive()) {
1006  // No heartbeat in a second. IO thread is dead?! Very Not Good.
1007  return true;
1008  }
1009 
1010  return false;
1011 }
1012 
1013 
1014 void DataFlash_File::vehicle_was_disarmed()
1015 {
1017  // rotate our log. Closing the current one and letting the
1018  // logging restart naturally based on log_disarmed should do
1019  // the trick:
1020  stop_logging();
1021  }
1022 }
1023 
1024 
1025 
1027 // функция конвертации между UNIX-временем и обычным представлением в виде даты и времени суток
1028 #define _TBIAS_DAYS ((70 * (uint32_t)365) + 17)
1029 #define _TBIAS_SECS (_TBIAS_DAYS * (xtime_t)86400)
1030 #define _TBIAS_YEAR 1900
1031 #define MONTAB(year) ((((year) & 03) || ((year) == 0)) ? mos : lmos)
1032 
1033 const uint16_t lmos[] = {0, 31, 60, 91, 121, 152, 182, 213, 244, 274, 305, 335};
1034 const uint16_t mos[] = {0, 31, 59, 90, 120, 151, 181, 212, 243, 273, 304, 334};
1035 
1036 #define Daysto32(year, mon) (((year - 1) / 4) + MONTAB(year)[mon])
1037 
1038 uint32_t DataFlash_File::to_timestamp(const struct tm *t)
1039 { /* convert time structure to scalar time */
1040  int32_t days;
1041  uint32_t secs;
1042  int32_t mon, year;
1043 
1044  /* Calculate number of days. */
1045  mon = t->tm_mon - 1;
1046  year = t->tm_year - _TBIAS_YEAR;
1047  days = Daysto32(year, mon) - 1;
1048  days += 365 * year;
1049  days += t->tm_mday;
1050  days -= _TBIAS_DAYS;
1051 
1052  /* Calculate number of seconds. */
1053  secs = 3600 * t->tm_hour;
1054  secs += 60 * t->tm_min;
1055  secs += t->tm_sec;
1056 
1057  secs += (days * (uint32_t)86400);
1058 
1059  return (secs);
1060 }
1061 #endif
int printf(const char *fmt,...)
Definition: stdio.c:113
bool get_soft_armed() const
Definition: Util.h:15
virtual void stop_logging(void)=0
DFMessageWriter_DFLogStart * _startup_messagewriter
WORD fdate
Definition: ff.h:228
Definition: ff.h:226
virtual bool CardInserted(void) const =0
virtual const char * get_custom_log_directory() const
Definition: Util.h:21
virtual bool StartNewLogOK() const
virtual void start_new_log_reset_variables()
Interface definition for the various Ground Control System.
virtual void Init()
struct DataFlash_Class::@194 _params
WORD ftime
Definition: ff.h:229
AP_HAL::Util * util
Definition: HAL.h:115
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
GCS & gcs()
static HAL_state state
virtual Semaphore * new_semaphore(void)
Definition: Util.h:108
#define MIN(a, b)
Definition: usb_conf.h:215
Definition: ff.h:246
virtual uint16_t find_last_log()=0
virtual bool WriteBlockCheckStartupMessages()
uint32_t millis()
Definition: system.cpp:157
bool log_while_disarmed(void) const
Definition: DataFlash.h:188
AP_Int8 file_bufsize
Definition: DataFlash.h:197
FRESULT
Definition: ff.h:243
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
void * malloc(size_t size)
Definition: malloc.c:61
void free(void *ptr)
Definition: malloc.c:81
Common definitions and utility routines for the ArduPilot libraries.
DataFlash_Class & _front
static uint16_t log_num
virtual void register_io_process(AP_HAL::MemberProc)=0
int snprintf(char *str, size_t size, const char *fmt,...)
Definition: stdio.c:64
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
virtual uint16_t start_new_log(void)=0
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
virtual void push_log_blocks()
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
uint8_t sd_busy
virtual bool logging_started(void) const =0
AP_Int8 file_disarm_rot
Definition: DataFlash.h:198