16 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT && (defined(BOARD_SDCARD_NAME) || defined(BOARD_DATAFLASH_FATFS)) 30 #if defined(BOARD_DATAFLASH_FATFS) 31 #define MAX_LOG_FILES 9U 33 #define MAX_LOG_FILES 50U 36 #define DATAFLASH_PAGE_SIZE 1024UL 38 #define MAX_FILE_SIZE 2048 * 1024L // not more 2MB 45 const char *log_directory) :
49 _log_directory(log_directory),
55 void DataFlash_File::Init()
62 if (semaphore ==
nullptr) {
70 if (custom_dir !=
nullptr){
71 _log_directory = custom_dir;
74 if (! SD.exists(_log_directory) ) {
78 for(cp=_log_directory + strlen(_log_directory);cp>_log_directory && *cp !=
'/';cp--){ }
79 for(wp=buf, rp=_log_directory; rp<cp;){
85 if (!SD.mkdir(_log_directory)) {
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));
101 while (!_writebuf.set_size(bufsize) && bufsize >= _writebuf_chunk) {
102 printf(
"DataFlash_File: Couldn't set buffer size to=%u\n", (
unsigned)bufsize);
106 if (!_writebuf.get_size()) {
107 printf(
"Out of memory for logging\n");
111 printf(
"DataFlash_File: buffer size=%u\n", (
unsigned)bufsize);
117 bool DataFlash_File::file_exists(
const char *filename)
const 119 return SD.exists(filename);
122 bool DataFlash_File::log_exists(
const uint16_t lognum)
const 124 char *filename = _log_file_name(lognum);
125 if (filename ==
nullptr) {
129 bool ret = file_exists(filename);
134 void DataFlash_File::periodic_1Hz(
const uint32_t now)
136 if (!(_write_fd) || !
_initialised || _open_error || _busy)
return;
138 if (!io_thread_alive()) {
139 gcs().
send_text(MAV_SEVERITY_WARNING,
"No IO Thread Heartbeat");
145 printf(
"\nLoging aborted\n");
151 void DataFlash_File::periodic_fullrate(
const uint32_t now)
156 uint32_t DataFlash_File::bufferspace_available()
158 const uint32_t space = _writebuf.space();
159 const uint32_t crit = critical_message_reserved_space();
161 return (space > crit) ? space - crit : 0;
165 bool DataFlash_File::CardInserted(
void)
const 172 float DataFlash_File::avail_space_percent(uint32_t *
free)
176 int32_t avail = SD.getfree(_log_directory, &space);
177 if(free) *free = avail;
182 return (avail/(
float)space) * 100;
185 #if 0 // why such hard? 189 uint16_t DataFlash_File::find_oldest_log()
191 if (_cached_oldest_log != 0) {
192 return _cached_oldest_log;
196 if (last_log_num == 0) {
200 uint16_t current_oldest_log = 0;
205 File dir = SD.open(_log_directory);
208 printf(
"error opening logs dir: %s", SD.strError(SD.lastError));
214 File de=dir.openNextFile();
217 printf(
"error scanning logs: %s", SD.strError(SD.lastError));
222 char *nm = de.name();
225 uint8_t length = strlen(nm);
230 if (strncmp(&nm[length-4],
".BIN", 4)) {
235 uint16_t thisnum = strtoul(nm,
nullptr, 10);
236 if (current_oldest_log == 0) {
237 current_oldest_log = thisnum;
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;
246 if (thisnum > last_log_num) {
247 if (thisnum < current_oldest_log) {
248 current_oldest_log = thisnum;
255 _cached_oldest_log = current_oldest_log;
257 return current_oldest_log;
263 uint16_t DataFlash_File::find_oldest_log()
266 if (_cached_oldest_log != 0) {
267 return _cached_oldest_log;
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;
284 void DataFlash_File::Prep_MinSpace()
286 const uint16_t first_log_to_remove = find_oldest_log();
287 if (first_log_to_remove != 0) {
289 _last_oldest_log = _cached_oldest_log + 1;
290 _cached_oldest_log = 0;
292 uint16_t log_to_remove = first_log_to_remove;
297 float avail = avail_space_percent(&free_sp);
300 #if defined(BOARD_DATAFLASH_FATFS) 301 printf(
"error getting free space, formatting!\n");
302 SD.format(_log_directory);
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);
314 if (avail >= min_avail_space_percent && free_sp*512 >= MAX_FILE_SIZE) {
317 if (count++ > MAX_LOG_FILES+10) {
321 char *filename_to_remove = _log_file_name(log_to_remove);
322 if (filename_to_remove ==
nullptr) {
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));
331 free(filename_to_remove);
334 if (log_to_remove > MAX_LOG_FILES) {
337 }
while (log_to_remove != first_log_to_remove);
341 #if defined(BOARD_DATAFLASH_FATFS) 342 float avail = avail_space_percent();
344 printf(
"erase don't get free space, formatting!\n");
345 SD.format(_log_directory);
352 void DataFlash_File::Prep() {
360 bool DataFlash_File::NeedPrep()
367 if (avail_space_percent() < min_avail_space_percent) {
378 char *DataFlash_File::_log_file_name(
const uint16_t
log_num)
const 380 char *buf = (
char *)
malloc(256);
381 if(!buf)
return nullptr;
383 sprintf(buf,
"%s/%u.BIN", _log_directory, (
unsigned)log_num);
392 char *DataFlash_File::_lastlog_file_name(
void)
const 394 char *buf = (
char *)
malloc(256);
395 if(!buf)
return nullptr;
397 sprintf(buf,
"%s/LASTLOG.TXT", _log_directory);
403 void DataFlash_File::EraseAll()
406 const bool was_logging = (_write_fd != -1);
409 for (log_num=1; log_num<=MAX_LOG_FILES; log_num++) {
410 char *fname = _log_file_name(log_num);
411 if (fname ==
nullptr) {
417 char *fname = _lastlog_file_name();
418 if (fname !=
nullptr) {
423 _cached_oldest_log = 0;
431 bool DataFlash_File::WritesOK()
const 443 bool DataFlash_File::StartNewLogOK()
const 453 bool DataFlash_File::_WritePrioritisedBlock(
const void *pBuffer, uint16_t size,
bool is_critical)
460 if (!semaphore->take(1)) {
464 uint32_t space = _writebuf.space();
472 if (space < non_messagewriter_message_reserved_space()) {
479 if (!is_critical && space < critical_message_reserved_space()) {
490 printf(
"dropping block! size=%d\n", size);
497 _writebuf.write((uint8_t*)pBuffer, size);
507 bool DataFlash_File::ReadBlock(
void *pkt, uint16_t size)
513 memset(pkt, 0, size);
514 if (_read_fd.read(pkt, size) != size) {
517 _read_offset += size;
525 uint16_t DataFlash_File::find_last_log()
528 char *fname = _lastlog_file_name();
529 if (fname ==
nullptr) {
532 File fd = SD.open(fname, FILE_READ);
536 memset(buf, 0,
sizeof(buf));
537 if (fd.read(buf,
sizeof(buf)-1) > 0) {
538 ret = strtoul(buf,
nullptr, 10);
546 uint32_t DataFlash_File::_get_log_size(
const uint16_t log_num)
const 548 char *fname = _log_file_name(log_num);
549 if (fname ==
nullptr) {
553 File fd = SD.open(fname, FILE_READ);
558 uint32_t sz= fd.size();
564 uint32_t DataFlash_File::_get_log_time(
const uint16_t log_num)
const 566 char *fname = _log_file_name(log_num);
567 if (fname ==
nullptr) {
573 int8_t ret = SD.stat(fname, &fno);
578 uint16_t date=fno.
fdate,
584 t.tm_sec = FAT_SECOND(time);
585 t.tm_min = FAT_MINUTE(time);
586 t.tm_hour = FAT_HOUR(time);
587 t.tm_mday = FAT_DAY(date);
588 t.tm_mon = FAT_MONTH(date);
589 t.tm_year = FAT_YEAR(date);
594 return to_timestamp(&t);
604 uint16_t DataFlash_File::_log_num_from_list_entry(
const uint16_t list_entry)
606 uint16_t oldest_log = find_oldest_log();
607 if (oldest_log == 0) {
612 uint32_t log_num = oldest_log + list_entry - 1;
614 if (log_num > MAX_LOG_FILES) {
615 log_num -= MAX_LOG_FILES;
617 while(!log_exists(log_num)){
619 if(log_num>MAX_LOG_FILES) {
620 log_num=MAX_LOG_FILES;
631 void DataFlash_File::get_log_boundaries(
const uint16_t list_entry, uint16_t & start_page, uint16_t & end_page)
633 const uint16_t log_num = _log_num_from_list_entry(list_entry);
635 if (! log_exists(log_num)) {
643 end_page = _get_log_size(log_num) / DATAFLASH_PAGE_SIZE;
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)
655 const uint16_t log_num = _log_num_from_list_entry(list_entry);
661 if (_read_fd && log_num != _read_fd_log_num) {
665 char *fname = _log_file_name(log_num);
666 if (fname ==
nullptr) {
670 _read_fd = SD.open(fname, O_RDONLY);
674 printf(
"Log read open fail for %s: %s\n", fname, SD.strError(SD.lastError));
683 int16_t ret = (int16_t)_read_fd.read(data, len);
693 void DataFlash_File::get_log_info(
const uint16_t list_entry, uint32_t &size, uint32_t &time_utc)
695 uint16_t log_num = _log_num_from_list_entry(list_entry);
697 if (! log_exists(log_num)) {
705 size = _get_log_size(log_num);
706 time_utc = _get_log_time(log_num);
714 uint16_t DataFlash_File::get_num_logs()
719 for (i=high; i>0; i--) {
722 if(_cached_oldest_log == 0 || i<_cached_oldest_log)
723 _cached_oldest_log=i;
728 for (i=MAX_LOG_FILES; i>high; i--) {
729 if ( log_exists(i)) {
731 if(_cached_oldest_log == 0 || i<_cached_oldest_log)
732 _cached_oldest_log=i;
742 void DataFlash_File::stop_logging(
void)
750 void DataFlash_File::PrepForArming()
761 uint16_t DataFlash_File::start_new_log(
void)
779 if (_get_log_size(log_num) > 0 || log_num == 0) {
782 if (log_num > MAX_LOG_FILES) {
785 _cached_oldest_log = 0;
792 fname = _log_file_name(log_num);
793 if (fname ==
nullptr) {
798 _write_fd = SD.open(fname, O_WRITE|O_CREAT|O_TRUNC);
806 printf(
"Log open fail for %s: %s\n",fname, SD.strError(SD.lastError));
811 printf(
"\nLoging aborted\n");
817 if (log_num >= MAX_LOG_FILES) {
822 printf(
"\nLoging stopped\n");
833 fname = _lastlog_file_name();
835 File fd = SD.open(fname, O_WRITE|O_CREAT);
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);
847 if (written < to_write) {
854 void DataFlash_File::_io_timer(
void)
857 _io_timer_heartbeat = tnow;
859 if (!(_write_fd) || !
_initialised || _open_error || !has_data) {
863 uint32_t nbytes = _writebuf.available();
867 if (nbytes < _writebuf_chunk &&
868 tnow - _last_write_time < 2000UL) {
875 _last_write_time = tnow;
876 if (nbytes > _writebuf_chunk) {
878 nbytes = _writebuf_chunk;
882 const uint8_t *head = _writebuf.readptr(size);
883 nbytes =
MIN(nbytes, size);
886 if ((nbytes + _write_offset) % 512 != 0) {
887 uint32_t ofs = (nbytes + _write_offset) % 512;
893 if(nbytes==0)
return;
895 ssize_t nwritten = _write_fd.write(head, nbytes);
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));
902 #if defined(BOARD_DATAFLASH_FATFS) 904 gcs().
send_text(MAV_SEVERITY_INFO,
"Formatting DataFlash, please wait");
907 SD.format(_log_directory);
912 nwritten = _write_fd.write(head, nbytes);
914 _write_offset += nwritten;
915 _writebuf.advance(nwritten);
923 gcs().
send_text(MAV_SEVERITY_INFO,
"logging cancelled");
935 nwritten = _write_fd.write(head, nbytes);
937 _write_offset += nwritten;
938 _writebuf.advance(nwritten);
947 _write_offset += nwritten;
948 _writebuf.advance(nwritten);
957 #if defined(BOARD_DATAFLASH_FATFS) // limit file size in some MBytes and reopen new log file 959 if(_write_fd.size() >= MAX_FILE_SIZE) {
973 bool DataFlash_File::logging_enabled()
const 982 bool DataFlash_File::io_thread_alive()
const 986 if(_io_timer_heartbeat + 5000 > tnow)
return true;
991 bool DataFlash_File::logging_failed()
const 995 if(_write_fd) op=
true;
1005 if (!io_thread_alive()) {
1014 void DataFlash_File::vehicle_was_disarmed()
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) 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};
1036 #define Daysto32(year, mon) (((year - 1) / 4) + MONTAB(year)[mon]) 1038 uint32_t DataFlash_File::to_timestamp(
const struct tm *t)
1045 mon = t->tm_mon - 1;
1046 year = t->tm_year - _TBIAS_YEAR;
1047 days = Daysto32(year, mon) - 1;
1050 days -= _TBIAS_DAYS;
1053 secs = 3600 * t->tm_hour;
1054 secs += 60 * t->tm_min;
1057 secs += (days * (uint32_t)86400);
int printf(const char *fmt,...)
bool get_soft_armed() const
virtual void stop_logging(void)=0
DFMessageWriter_DFLogStart * _startup_messagewriter
virtual bool CardInserted(void) const =0
virtual const char * get_custom_log_directory() const
virtual bool StartNewLogOK() const
virtual void start_new_log_reset_variables()
Interface definition for the various Ground Control System.
struct DataFlash_Class::@194 _params
bool _writing_startup_messages
virtual Semaphore * new_semaphore(void)
virtual uint16_t find_last_log()=0
virtual bool WriteBlockCheckStartupMessages()
bool log_while_disarmed(void) const
void send_text(MAV_SEVERITY severity, const char *fmt,...)
void * malloc(size_t size)
Common definitions and utility routines for the ArduPilot libraries.
virtual void register_io_process(AP_HAL::MemberProc)=0
int snprintf(char *str, size_t size, const char *fmt,...)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
virtual uint16_t start_new_log(void)=0
void panic(const char *errormsg,...) FMT_PRINTF(1
virtual void push_log_blocks()
AP_HAL::Scheduler * scheduler
virtual bool logging_started(void) const =0