Copter: free allocations in case of allocation failure
[ardupilot.git] / libraries / AP_Logger / AP_Logger_Block.cpp
blob07357c833a9d2636b0fbbd8b5078a48af7c8e998
1 /*
2 block based logging, for boards with flash logging
3 */
5 #include "AP_Logger_config.h"
7 #if HAL_LOGGING_BLOCK_ENABLED
9 #include "AP_Logger_Block.h"
10 #include "AP_Logger.h"
11 #include <AP_HAL/AP_HAL.h>
12 #include <stdio.h>
13 #include <AP_RTC/AP_RTC.h>
14 #include <GCS_MAVLink/GCS.h>
16 const extern AP_HAL::HAL& hal;
18 // the last page holds the log format in first 4 bytes. Please change
19 // this if (and only if!) the low level format changes
20 #define DF_LOGGING_FORMAT 0x1901201B
22 AP_Logger_Block::AP_Logger_Block(AP_Logger &front, LoggerMessageWriter_DFLogStart *writer) :
23 AP_Logger_Backend(front, writer),
24 writebuf(0)
26 df_stats_clear();
29 // Init() is called after driver Init(), it is the responsibility of the driver to make sure the
30 // device is ready to accept commands before Init() is called
31 void AP_Logger_Block::Init(void)
33 // buffer is used for both reads and writes so access must always be within the semaphore
34 buffer = (uint8_t *)hal.util->malloc_type(df_PageSize, AP_HAL::Util::MEM_DMA_SAFE);
35 if (buffer == nullptr) {
36 AP_HAL::panic("Out of DMA memory for logging");
39 //flash_test();
41 if (CardInserted()) {
42 // reserve space for version in last sector
43 df_NumPages -= df_PagePerBlock;
45 // determine and limit file backend buffersize
46 uint32_t bufsize = _front._params.file_bufsize;
47 if (bufsize > 64) {
48 bufsize = 64;
50 bufsize *= 1024;
52 // If we can't allocate the full size, try to reduce it until we can allocate it
53 while (!writebuf.set_size(bufsize) && bufsize >= df_PageSize * df_PagePerBlock) {
54 DEV_PRINTF("AP_Logger_Block: Couldn't set buffer size to=%u\n", (unsigned)bufsize);
55 bufsize >>= 1;
58 if (!writebuf.get_size()) {
59 DEV_PRINTF("Out of memory for logging\n");
60 return;
63 DEV_PRINTF("AP_Logger_Block: buffer size=%u\n", (unsigned)bufsize);
64 _initialised = true;
67 WITH_SEMAPHORE(sem);
69 if (NeedErase()) {
70 EraseAll();
71 } else {
72 validate_log_structure();
76 uint32_t AP_Logger_Block::bufferspace_available()
78 // because AP_Logger_Block devices are ring buffers, we *always*
79 // have room...
80 return df_NumPages * df_PageSize;
83 // *** LOGGER PUBLIC FUNCTIONS ***
84 void AP_Logger_Block::StartWrite(uint32_t PageAdr)
86 df_PageAdr = PageAdr;
89 void AP_Logger_Block::FinishWrite(void)
91 // Write Buffer to flash
92 BufferToPage(df_PageAdr);
93 df_PageAdr++;
95 // If we reach the end of the memory, start from the beginning
96 if (df_PageAdr > df_NumPages) {
97 df_PageAdr = 1;
100 // when starting a new sector, erase it
101 if ((df_PageAdr-1) % df_PagePerBlock == 0) {
102 // if we have wrapped over an existing log, force the oldest to be recalculated
103 if (_cached_oldest_log > 0) {
104 uint16_t log_num = StartRead(df_PageAdr);
105 if (log_num != 0xFFFF && log_num >= _cached_oldest_log) {
106 _cached_oldest_log = 0;
109 // are we about to erase a sector with our own headers in it?
110 if (df_Write_FilePage > df_NumPages - df_PagePerBlock) {
111 chip_full = true;
112 return;
114 SectorErase(get_block(df_PageAdr));
118 bool AP_Logger_Block::WritesOK() const
120 if (!CardInserted() || erase_started) {
121 return false;
123 return true;
126 bool AP_Logger_Block::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
128 // is_critical is ignored - we're a ring buffer and never run out
129 // of space. possibly if we do more complicated bandwidth
130 // limiting we can reserve bandwidth based on is_critical
131 if (!WritesOK()) {
132 return false;
135 WITH_SEMAPHORE(write_sem);
137 const uint32_t space = writebuf.space();
139 if (_writing_startup_messages &&
140 _startup_messagewriter->fmt_done()) {
141 // the state machine has called us, and it has finished
142 // writing format messages out. It can always get back to us
143 // with more messages later, so let's leave room for other
144 // things:
145 const uint32_t now = AP_HAL::millis();
146 const bool must_dribble = (now - last_messagewrite_message_sent) > 100;
147 if (!must_dribble &&
148 space < non_messagewriter_message_reserved_space(writebuf.get_size())) {
149 // this message isn't dropped, it will be sent again...
150 return false;
152 last_messagewrite_message_sent = now;
153 } else {
154 // we reserve some amount of space for critical messages:
155 if (!is_critical && space < critical_message_reserved_space(writebuf.get_size())) {
156 _dropped++;
157 return false;
161 // if no room for entire message - drop it:
162 if (space < size) {
163 _dropped++;
164 return false;
167 writebuf.write((uint8_t*)pBuffer, size);
168 df_stats_gather(size, writebuf.space());
170 return true;
173 // read from the page address and return the file number at that location
174 uint16_t AP_Logger_Block::StartRead(uint32_t PageAdr)
176 // copy flash page to buffer
177 if (erase_started) {
178 df_Read_PageAdr = PageAdr;
179 memset(buffer, 0xff, df_PageSize);
180 } else {
181 PageToBuffer(PageAdr);
183 return ReadHeaders();
186 // read the headers at the current read point returning the file number
187 uint16_t AP_Logger_Block::ReadHeaders()
189 // We are starting a new page - read FileNumber and FilePage
190 struct PageHeader ph;
191 BlockRead(0, &ph, sizeof(ph));
192 df_FileNumber = ph.FileNumber;
193 df_FilePage = ph.FilePage;
194 #if BLOCK_LOG_VALIDATE
195 if (ph.crc != DF_LOGGING_FORMAT + df_FilePage && df_FileNumber != 0xFFFF) {
196 printf("ReadHeaders: invalid block read at %d\n", df_Read_PageAdr);
198 #endif
199 df_Read_BufferIdx = sizeof(ph);
200 // we are at the start of a file, read the file header
201 if (df_FilePage == 1) {
202 struct FileHeader fh;
203 BlockRead(sizeof(ph), &fh, sizeof(fh));
204 df_FileTime = fh.utc_secs;
205 df_Read_BufferIdx += sizeof(fh);
208 return df_FileNumber;
211 bool AP_Logger_Block::ReadBlock(void *pBuffer, uint16_t size)
213 if (erase_started) {
214 return false;
216 while (size > 0) {
217 uint16_t n = df_PageSize - df_Read_BufferIdx;
218 if (n > size) {
219 n = size;
222 if (!BlockRead(df_Read_BufferIdx, pBuffer, n)) {
223 return false;
225 size -= n;
226 pBuffer = (void *)(n + (uintptr_t)pBuffer);
228 df_Read_BufferIdx += n;
230 if (df_Read_BufferIdx == df_PageSize) {
231 uint32_t new_page_addr = df_Read_PageAdr + 1;
232 if (new_page_addr > df_NumPages) {
233 new_page_addr = 1;
235 if (erase_started) {
236 memset(buffer, 0xff, df_PageSize);
237 df_Read_PageAdr = new_page_addr;
238 } else {
239 PageToBuffer(new_page_addr);
242 // We are starting a new page - read FileNumber and FilePage
243 ReadHeaders();
246 return true;
249 // initialize the log data for the given file number
250 void AP_Logger_Block::StartLogFile(uint16_t FileNumber)
252 df_FileNumber = FileNumber;
253 df_Write_FileNumber = FileNumber;
254 df_FilePage = 1;
255 df_Write_FilePage = 1;
258 uint16_t AP_Logger_Block::GetFileNumber() const
260 return df_FileNumber;
263 void AP_Logger_Block::EraseAll()
265 if (hal.util->get_soft_armed()) {
266 // do not want to do any filesystem operations while we are e.g. flying
267 return;
270 // push out the message before stopping logging
271 if (!erase_started) {
272 GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Chip erase started");
275 WITH_SEMAPHORE(sem);
277 if (erase_started) {
278 // already erasing
279 return;
281 erase_started = true;
283 // remember what we were doing
284 new_log_pending = log_write_started;
286 // throw away everything
287 log_write_started = false;
288 writebuf.clear();
290 // reset the format version and wrapped status so that any incomplete erase will be caught
291 Sector4kErase(get_sector(df_NumPages));
293 StartErase();
296 void AP_Logger_Block::periodic_1Hz()
298 AP_Logger_Backend::periodic_1Hz();
300 if (rate_limiter == nullptr &&
301 (_front._params.blk_ratemax > 0 ||
302 _front._params.disarm_ratemax > 0 ||
303 _front._log_pause)) {
304 // setup rate limiting if log rate max > 0Hz or log pause of streaming entries is requested
305 rate_limiter = NEW_NOTHROW AP_Logger_RateLimiter(_front, _front._params.blk_ratemax, _front._params.disarm_ratemax);
308 if (!io_thread_alive()) {
309 if (warning_decimation_counter == 0 && _initialised) {
310 // we don't print this error unless we did initialise. When _initialised is set to true
311 // we register the IO timer callback
312 GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "AP_Logger: IO thread died");
314 if (warning_decimation_counter++ > 57) {
315 warning_decimation_counter = 0;
317 _initialised = false;
318 } else if (chip_full) {
319 if (warning_decimation_counter == 0) {
320 GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Chip full, logging stopped");
322 if (warning_decimation_counter++ > 57) {
323 warning_decimation_counter = 0;
328 // EraseAll is asynchronous, but we must not start a new
329 // log in a child thread so this task picks up the hint from the io timer
330 // keeping locking to a minimum
331 void AP_Logger_Block::periodic_10Hz(const uint32_t now)
333 if (erase_started || InErase()) {
334 return;
337 // don't print status messages in io thread, do it here
338 switch (status_msg) {
339 case StatusMessage::ERASE_COMPLETE:
340 GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Chip erase complete");
341 status_msg = StatusMessage::NONE;
342 break;
343 case StatusMessage::RECOVERY_COMPLETE:
344 GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Log recovery complete");
345 status_msg = StatusMessage::NONE;
346 break;
347 case StatusMessage::NONE:
348 break;
351 // EraseAll should only set this in the main thread
352 if (new_log_pending) {
353 start_new_log();
358 * we need to erase if the logging format has changed
360 bool AP_Logger_Block::NeedErase(void)
362 uint32_t version = 0;
363 PageToBuffer(df_NumPages+1); // last page
364 BlockRead(0, &version, sizeof(version));
365 if (version == DF_LOGGING_FORMAT) {
366 // only leave the read point in a sane place if we are not about to destroy everything
367 StartRead(1);
368 return false;
370 return true;
374 * iterate through all of the logs files looking for ones that are corrupted and correct.
376 void AP_Logger_Block::validate_log_structure()
378 WITH_SEMAPHORE(sem);
379 bool wrapped = is_wrapped();
380 uint32_t page = 1;
381 uint32_t page_start = 1;
383 uint16_t file = StartRead(page);
384 uint16_t first_file = file;
385 uint16_t next_file = file;
386 uint16_t last_file = 0;
388 while (file != 0xFFFF && page <= df_NumPages && (file == next_file || (wrapped && file < next_file))) {
389 uint32_t end_page = find_last_page_of_log(file);
390 if (end_page == 0 || end_page < page) { // this can happen and may be responsible for corruption that we have seen
391 break;
393 page = end_page + 1;
394 file = StartRead(page);
395 next_file++;
396 // skip over the rest of an erased block
397 if (wrapped && file == 0xFFFF) {
398 file = StartRead((get_block(page) + 1) * df_PagePerBlock + 1);
400 if (wrapped && file < next_file) {
401 page_start = page;
402 next_file = file;
403 first_file = file;
404 } else if (last_file < next_file) {
405 last_file = file;
407 if (file == next_file) {
408 DEV_PRINTF("Found complete log %d at %X-%X\n", int(file), unsigned(page), unsigned(find_last_page_of_log(file)));
412 if (file != 0xFFFF && file != next_file && page <= df_NumPages && page > 0) {
413 DEV_PRINTF("Found corrupt log %d at 0x%04X, erasing", int(file), unsigned(page));
414 df_EraseFrom = page;
415 } else if (next_file != 0xFFFF && page > 0 && next_file > 1) { // chip is empty
416 DEV_PRINTF("Found %d complete logs at 0x%04X-0x%04X", int(next_file - first_file), unsigned(page_start), unsigned(page - 1));
421 * get raw data from a log - page is the start page of the log, offset is the offset within the log starting at that page
423 int16_t AP_Logger_Block::get_log_data_raw(uint16_t log_num, uint32_t page, uint32_t offset, uint16_t len, uint8_t *data)
425 WITH_SEMAPHORE(sem);
426 const uint16_t data_page_size = df_PageSize - sizeof(struct PageHeader);
427 const uint16_t first_page_size = data_page_size - sizeof(struct FileHeader);
429 // offset is the true offset in the file, so we have to calculate the offset accounting for page headers
430 if (offset >= first_page_size) {
431 offset -= first_page_size;
432 page = page + offset / data_page_size + 1;
433 offset %= data_page_size;
435 if (page > df_NumPages) {
436 page = page % df_NumPages;
440 // Sanity check we haven't been asked for an offset beyond the end of the log
441 if (StartRead(page) != log_num) {
442 return -1;
445 df_Read_BufferIdx += offset;
447 if (!ReadBlock(data, len)) {
448 return -1;
451 return (int16_t)len;
455 get data from a log, accounting for adding FMT headers
457 int16_t AP_Logger_Block::get_log_data(uint16_t list_entry, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)
459 const uint16_t log_num = log_num_from_list_entry(list_entry);
461 if (log_num == 0) {
462 // that failed - probably no logs
463 return -1;
466 //printf("get_log_data(%d, %d, %d, %d)\n", log_num, page, offset, len);
467 WITH_SEMAPHORE(sem);
469 uint16_t ret = 0;
470 if (len > 0) {
471 const int16_t bytes = get_log_data_raw(log_num, page, offset, len, data);
472 if (bytes == -1) {
473 return -1;
475 ret += bytes;
478 return ret;
482 // This function determines the number of whole log files in the AP_Logger
483 // partial logs are rejected as without the headers they are relatively useless
484 uint16_t AP_Logger_Block::get_num_logs(void)
486 WITH_SEMAPHORE(sem);
487 uint32_t lastpage;
488 uint32_t last;
490 if (!CardInserted() || find_last_page() == 1) {
491 return 0;
494 uint32_t first = StartRead(1);
496 if (first == 0xFFFF) {
497 return 0;
500 lastpage = find_last_page();
501 last = StartRead(lastpage);
503 if (is_wrapped()) {
504 // if we wrapped then the rest of the block will be filled with 0xFFFF because we always erase
505 // a block before writing to it, in order to find the first page we therefore have to read after the
506 // next block boundary
507 first = StartRead((get_block(lastpage) + 1) * df_PagePerBlock + 1);
508 // unless we happen to land on the first page of the file that is being overwritten we skip to the next file
509 if (df_FilePage > 1) {
510 first++;
514 if (last == first) {
515 return 1;
518 return (last - first + 1);
521 // stop logging immediately
522 void AP_Logger_Block::stop_logging(void)
524 WITH_SEMAPHORE(sem);
526 log_write_started = false;
528 // nuke writing any previous log
529 writebuf.clear();
532 // stop logging and flush any remaining data
533 void AP_Logger_Block::stop_logging_async(void)
535 stop_log_pending = true;
538 // This function starts a new log file in the AP_Logger
539 // no actual data should be written to the storage here
540 // that should all be handled by the IO thread
541 void AP_Logger_Block::start_new_log(void)
543 if (erase_started) {
544 // currently erasing
545 return;
548 WITH_SEMAPHORE(sem);
550 if (logging_started()) {
551 stop_logging();
554 // no need to schedule this anymore
555 new_log_pending = false;
557 uint32_t last_page = find_last_page();
559 StartRead(last_page);
561 log_write_started = true;
562 uint16_t new_log_num = 1;
564 if (find_last_log() == 0 || GetFileNumber() == 0xFFFF) {
565 StartLogFile(new_log_num);
566 StartWrite(1);
567 // Check for log of length 1 page and suppress
568 } else if (df_FilePage <= 1) {
569 new_log_num = GetFileNumber();
570 // Last log too short, reuse its number
571 // and overwrite it
572 StartLogFile(new_log_num);
573 StartWrite(last_page);
574 } else {
575 new_log_num = GetFileNumber()+1;
576 if (last_page == 0xFFFF) {
577 last_page=0;
579 StartLogFile(new_log_num);
580 StartWrite(last_page + 1);
583 // save UTC time in the first 4 bytes so that we can retrieve it later
584 uint64_t utc_usec;
585 FileHeader hdr {};
586 if (AP::rtc().get_utc_usec(utc_usec)) {
587 hdr.utc_secs = utc_usec / 1000000U;
589 writebuf.write((uint8_t*)&hdr, sizeof(FileHeader));
591 start_new_log_reset_variables();
593 return;
596 // This function finds the first and last pages of a log file
597 // The first page may be greater than the last page if the AP_Logger has been filled and partially overwritten.
598 void AP_Logger_Block::get_log_boundaries(uint16_t list_entry, uint32_t & start_page, uint32_t & end_page)
600 const uint16_t log_num = log_num_from_list_entry(list_entry);
601 if (log_num == 0) {
602 // that failed - probably no logs
603 start_page = 0;
604 end_page = 0;
605 return;
608 WITH_SEMAPHORE(sem);
609 uint16_t num = get_num_logs();
610 uint32_t look;
612 end_page = find_last_page_of_log(log_num);
614 if (num == 1 || log_num == 1) {
615 if (!is_wrapped()) {
616 start_page = 1;
617 } else {
618 StartRead(end_page);
619 start_page = (end_page + df_NumPages - df_FilePage) % df_NumPages + 1;
621 } else {
622 // looking for the first log which might have a gap in front of it
623 if (list_entry == 1) {
624 StartRead(end_page);
625 if (end_page > df_FilePage) { // log is not wrapped
626 start_page = end_page - df_FilePage + 1;
627 } else { // log is wrapped
628 start_page = (end_page + df_NumPages - df_FilePage) % df_NumPages + 1;
630 } else {
631 look = log_num-1;
632 do {
633 start_page = find_last_page_of_log(look) + 1;
634 look--;
635 } while (start_page <= 0 && look >=1);
639 if (start_page == df_NumPages + 1 || start_page == 0) {
640 start_page = 1;
643 if (end_page == 0) {
644 end_page = start_page;
649 // return true if logging has wrapped around to the beginning of the chip
650 bool AP_Logger_Block::is_wrapped(void)
652 return StartRead(df_NumPages) != 0xFFFF;
656 // This function finds the last log number
657 uint16_t AP_Logger_Block::find_last_log(void)
659 WITH_SEMAPHORE(sem);
660 uint32_t last_page = find_last_page();
661 return StartRead(last_page);
664 // This function finds the last page of the last file
665 uint32_t AP_Logger_Block::find_last_page(void)
667 uint32_t look;
668 uint32_t bottom = 1;
669 uint32_t top = df_NumPages;
670 uint64_t look_hash;
671 uint64_t bottom_hash;
672 uint64_t top_hash;
674 WITH_SEMAPHORE(sem);
676 StartRead(bottom);
677 bottom_hash = ((int64_t)GetFileNumber()<<32) | df_FilePage;
679 while (top-bottom > 1) {
680 look = (top+bottom)/2;
681 StartRead(look);
682 look_hash = (int64_t)GetFileNumber()<<32 | df_FilePage;
683 // erased sector so can discount everything above
684 if (look_hash >= 0xFFFF00000000) {
685 look_hash = 0;
688 if (look_hash < bottom_hash) {
689 // move down
690 top = look;
691 } else {
692 // move up
693 bottom = look;
694 bottom_hash = look_hash;
698 StartRead(top);
699 top_hash = ((int64_t)GetFileNumber()<<32) | df_FilePage;
700 if (top_hash >= 0xFFFF00000000) {
701 top_hash = 0;
703 if (top_hash > bottom_hash) {
704 return top;
707 return bottom;
710 // This function finds the last page of a particular log file
711 uint32_t AP_Logger_Block::find_last_page_of_log(uint16_t log_number)
713 uint32_t look;
714 uint32_t bottom;
715 uint32_t top;
716 uint64_t look_hash;
717 uint64_t check_hash;
719 WITH_SEMAPHORE(sem);
721 if (is_wrapped()) {
722 bottom = StartRead(1);
723 if (bottom > log_number) {
724 bottom = find_last_page();
725 top = df_NumPages;
726 } else {
727 bottom = 1;
728 top = find_last_page();
730 } else {
731 bottom = 1;
732 top = find_last_page();
735 check_hash = (int64_t)log_number<<32 | 0xFFFFFFFF;
737 while (top-bottom > 1) {
738 look = (top+bottom)/2;
739 StartRead(look);
740 look_hash = (int64_t)GetFileNumber()<<32 | df_FilePage;
741 if (look_hash >= 0xFFFF00000000) {
742 look_hash = 0;
745 if (look_hash > check_hash) {
746 // move down
747 top = look;
748 } else {
749 // move up
750 bottom = look;
754 if (StartRead(top) == log_number) {
755 return top;
758 if (StartRead(bottom) == log_number) {
759 return bottom;
762 GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "No last page of log %d at top=%X or bot=%X", int(log_number), unsigned(top), unsigned(bottom));
763 return 0;
766 void AP_Logger_Block::get_log_info(uint16_t list_entry, uint32_t &size, uint32_t &time_utc)
768 uint32_t start, end;
770 WITH_SEMAPHORE(sem);
772 get_log_boundaries(list_entry, start, end);
773 if (end >= start) {
774 size = (end + 1 - start) * (uint32_t)(df_PageSize - sizeof(PageHeader));
775 } else {
776 size = (df_NumPages + end + 1 - start) * (uint32_t)(df_PageSize - sizeof(PageHeader));
779 size -= sizeof(FileHeader);
781 //printf("LOG %d(%d), %d-%d, size %d\n", log_num_from_list_entry(list_entry), list_entry, start, end, size);
783 StartRead(start);
785 // the log we are currently writing
786 if (df_FileTime == 0 && df_FileNumber == df_Write_FileNumber) {
787 uint64_t utc_usec;
788 if (AP::rtc().get_utc_usec(utc_usec)) {
789 df_FileTime = utc_usec / 1000000U;
792 time_utc = df_FileTime;
795 // read size bytes of data from the buffer
796 bool AP_Logger_Block::BlockRead(uint16_t IntPageAdr, void *pBuffer, uint16_t size)
798 memcpy(pBuffer, &buffer[IntPageAdr], size);
799 return true;
802 bool AP_Logger_Block::logging_failed() const
804 if (!_initialised) {
805 return true;
807 if (!io_thread_alive()) {
808 return true;
810 if (chip_full) {
811 return true;
814 return false;
817 // detect whether the IO thread is running, since this is considered a catastrophic failure for the logging system
818 // better be really, really sure
819 bool AP_Logger_Block::io_thread_alive() const
821 // if the io thread hasn't had a heartbeat in 3s it is dead
822 return (AP_HAL::millis() - io_timer_heartbeat) < 3000U || !hal.scheduler->is_system_initialized();
826 IO timer running on IO thread
827 The IO timer runs every 1ms or at 1Khz. The standard flash chip can write roughly 130Kb/s
828 so there is little point in trying to write more than 130 bytes - or 1 page (256 bytes).
829 The W25Q128FV datasheet gives tpp as typically 0.7ms yielding an absolute maximum rate of
830 365Kb/s or just over a page per cycle.
832 void AP_Logger_Block::io_timer(void)
834 uint32_t tnow = AP_HAL::millis();
835 io_timer_heartbeat = tnow;
837 // don't write anything for the first 2s to give the dataflash chip a chance to be ready
838 if (!_initialised || tnow < 2000) {
839 return;
842 if (erase_started) {
843 WITH_SEMAPHORE(sem);
845 if (InErase()) {
846 return;
848 // write the logging format in the last page
849 StartWrite(df_NumPages+1);
850 uint32_t version = DF_LOGGING_FORMAT;
851 memset(buffer, 0, df_PageSize);
852 memcpy(buffer, &version, sizeof(version));
853 FinishWrite();
854 erase_started = false;
855 chip_full = false;
856 status_msg = StatusMessage::ERASE_COMPLETE;
857 return;
860 if (df_EraseFrom > 0) {
861 WITH_SEMAPHORE(sem);
863 const uint32_t sectors = df_NumPages / df_PagePerSector;
864 const uint32_t block_size = df_PagePerBlock * df_PageSize;
865 const uint32_t sectors_in_block = block_size / (df_PagePerSector * df_PageSize);
866 uint32_t next_sector = get_sector(df_EraseFrom);
867 const uint32_t aligned_sector = sectors - (((df_NumPages - df_EraseFrom + 1) / df_PagePerSector) / sectors_in_block) * sectors_in_block;
868 while (next_sector < aligned_sector) {
869 Sector4kErase(next_sector);
870 io_timer_heartbeat = AP_HAL::millis();
871 next_sector++;
873 while (next_sector < sectors) {
874 SectorErase(next_sector / sectors_in_block);
875 io_timer_heartbeat = AP_HAL::millis();
876 next_sector += sectors_in_block;
878 status_msg = StatusMessage::RECOVERY_COMPLETE;
879 df_EraseFrom = 0;
882 if (!CardInserted() || new_log_pending || chip_full) {
883 return;
886 // we have been asked to stop logging, flush everything
887 if (stop_log_pending) {
888 WITH_SEMAPHORE(sem);
890 log_write_started = false;
892 // complete writing any previous log, a page at a time to avoid holding the lock for too long
893 if (writebuf.available()) {
894 write_log_page();
895 } else {
896 writebuf.clear();
897 stop_log_pending = false;
900 // write at most one page
901 } else if (writebuf.available() >= df_PageSize - sizeof(struct PageHeader)) {
902 WITH_SEMAPHORE(sem);
904 write_log_page();
908 // write out a page of log data
909 void AP_Logger_Block::write_log_page()
911 struct PageHeader ph;
912 ph.FileNumber = df_Write_FileNumber;
913 ph.FilePage = df_Write_FilePage;
914 #if BLOCK_LOG_VALIDATE
915 ph.crc = DF_LOGGING_FORMAT + df_Write_FilePage;
916 #endif
917 memcpy(buffer, &ph, sizeof(ph));
918 const uint32_t pagesize = df_PageSize - sizeof(ph);
919 uint32_t nbytes = writebuf.read(&buffer[sizeof(ph)], pagesize);
920 if (nbytes < pagesize) {
921 memset(&buffer[sizeof(ph) + nbytes], 0, pagesize - nbytes);
923 FinishWrite();
924 df_Write_FilePage++;
927 void AP_Logger_Block::flash_test()
929 uint32_t pages_to_check = 128;
930 for (uint32_t i=1; i<=pages_to_check; i++) {
931 if ((i-1) % df_PagePerBlock == 0) {
932 printf("Block erase %u\n", get_block(i));
933 SectorErase(get_block(i));
935 memset(buffer, uint8_t(i), df_PageSize);
936 if (i<5) {
937 printf("Flash fill 0x%x\n", uint8_t(i));
938 } else if (i==5) {
939 printf("Flash fill pages 5-%u\n", pages_to_check);
941 BufferToPage(i);
943 for (uint32_t i=1; i<=pages_to_check; i++) {
944 if (i<5) {
945 printf("Flash check 0x%x\n", uint8_t(i));
946 } else if (i==5) {
947 printf("Flash check pages 5-%u\n", pages_to_check);
949 PageToBuffer(i);
950 uint32_t bad_bytes = 0;
951 uint32_t first_bad_byte = 0;
952 for (uint32_t j=0; j<df_PageSize; j++) {
953 if (buffer[j] != uint8_t(i)) {
954 bad_bytes++;
955 if (bad_bytes == 1) {
956 first_bad_byte = j;
960 if (bad_bytes > 0) {
961 printf("Test failed: page %u, %u of %u bad bytes, first=0x%x\n",
962 i, bad_bytes, df_PageSize, buffer[first_bad_byte]);
966 // speed test
967 pages_to_check = 4096; // 1mB / 8mB
968 for (uint32_t i=1; i<=pages_to_check; i++) {
969 if ((i-1) % df_PagePerBlock == 0) {
970 SectorErase(get_block(i));
973 uint32_t now_ms = AP_HAL::millis();
974 for (uint32_t i=1; i<=pages_to_check; i++) {
975 BufferToPage(i);
977 printf("Flash speed test: %ukB/s\n", unsigned((pages_to_check * df_PageSize * 1000) / (1024 * (AP_HAL::millis() - now_ms))));
980 #endif // HAL_LOGGING_BLOCK_ENABLED