APM:Libraries
DataFlash_Revo.cpp
Go to the documentation of this file.
1 /*
2  hacked up DataFlash library for Desktop support
3 */
4 
5 
6 #include <AP_HAL/AP_HAL.h>
7 
8 
9 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT && defined(BOARD_DATAFLASH_CS_PIN) && !defined(BOARD_DATAFLASH_FATFS)
10 
11 #include "DataFlash_Revo.h"
12 
13 
14 #include <stdlib.h>
15 #include <stdio.h>
16 #include <sys/types.h>
17 #include <sys/stat.h>
18 #include <fcntl.h>
19 #include <stdint.h>
20 #include <assert.h>
21 
23 #include <AP_HAL_F4Light/GPIO.h>
24 
25 #pragma GCC diagnostic ignored "-Wunused-result"
26 
27 
28 extern const AP_HAL::HAL& hal;
29 
30 static uint8_t buffer[2][DF_PAGE_SIZE];
31 static uint8_t cmd[4];
32 
37 
38 
39 // the last page holds the log format in first 4 bytes. Please change
40 // this if (and only if!) the low level format changes
41 #define DF_LOGGING_FORMAT 0x28122013L
42 
44 {
45  // because DataFlash_Block devices are ring buffers, we *always*
46  // have room...
47  return df_NumPages * df_PageSize;
48 }
49 
50 // *** DATAFLASH PUBLIC FUNCTIONS ***
51 void DataFlash_Revo::StartWrite(uint16_t PageAdr)
52 {
53  df_BufferIdx = 0;
54  df_BufferNum = 0;
55  df_PageAdr = PageAdr;
56  WaitReady();
57 }
58 
60 {
61  // Write Buffer to flash, NO WAIT
63  df_PageAdr++;
64  // If we reach the end of the memory, start from the beginning
65  if (df_PageAdr > df_NumPages) {
66  df_PageAdr = 1;
67  }
68 
69 // TODO: а что, стирать уже не надо???
70  uint16_t block_num = df_PageAdr / (erase_size/DF_PAGE_SIZE); // number of erase block
71  uint16_t page_in_block = df_PageAdr % (erase_size/DF_PAGE_SIZE); // number of page in erase block
72 
73 // if(block_num != last_block_num){
74  if(page_in_block==0 || df_PageAdr==1){ // начали писАть страницу - подготовим ее
76  last_block_num = block_num;
77  }
78 
79  // switch buffer
80  df_BufferNum ^= 1;
81  df_BufferIdx = 0;
82 }
83 
84 bool DataFlash_Revo::WritesOK() const
85 {
86  if (!CardInserted()) {
87  return false;
88  }
89  if (!log_write_started) {
90  return false;
91  }
92  return true;
93 }
94 
95 bool DataFlash_Revo::_WritePrioritisedBlock(const void *pBuffer, uint16_t size,
96  bool is_critical)
97 {
98  // is_critical is ignored - we're a ring buffer and never run out
99  // of space. possibly if we do more complicated bandwidth
100  // limiting we can reservice bandwidth based on is_critical
101  if (!WritesOK()) {
102  return false;
103  }
104 
106  return false;
107  }
108 
109  while (size > 0) {
110  uint16_t n = df_PageSize - df_BufferIdx;
111  if (n > size) {
112  n = size;
113  }
114 
115  if (df_BufferIdx == 0) {
116  // if we are at the start of a page we need to insert a
117  // page header
118  if (n > df_PageSize - sizeof(struct PageHeader)) {
119  n = df_PageSize - sizeof(struct PageHeader);
120  }
121  struct PageHeader ph = { df_FileNumber, df_FilePage };
122  BlockWrite(df_BufferNum, df_BufferIdx, &ph, sizeof(ph), pBuffer, n);
123  df_BufferIdx += n + sizeof(ph);
124  } else {
125  BlockWrite(df_BufferNum, df_BufferIdx, nullptr, 0, pBuffer, n);
126  df_BufferIdx += n;
127  }
128 
129  size -= n;
130  pBuffer = (const void *)(n + (uintptr_t)pBuffer);
131 
132  if (df_BufferIdx == df_PageSize) {
133  FinishWrite();
134  df_FilePage++;
135  }
136  }
137 
138  return true;
139 }
140 
141 
142 // Get the last page written to
144 {
145  return df_PageAdr;
146 }
147 
148 // Get the last page read
149 uint16_t DataFlash_Revo::GetPage()
150 {
151  return df_Read_PageAdr;
152 }
153 
154 void DataFlash_Revo::StartRead(uint16_t PageAdr)
155 {
156  df_Read_BufferNum = 0;
157  df_Read_PageAdr = PageAdr;
158 
159  // disable writing while reading
160  log_write_started = false;
161 
162  WaitReady();
163 
164  // copy flash page to buffer
166 
167  // We are starting a new page - read FileNumber and FilePage
168  struct PageHeader ph;
169  BlockRead(df_Read_BufferNum, 0, &ph, sizeof(ph));
170  df_FileNumber = ph.FileNumber;
171  df_FilePage = ph.FilePage;
172  df_Read_BufferIdx = sizeof(ph);
173 }
174 
175 bool DataFlash_Revo::ReadBlock(void *pBuffer, uint16_t size)
176 {
177  while (size > 0) {
178  uint16_t n = df_PageSize - df_Read_BufferIdx;
179  if (n > size) {
180  n = size;
181  }
182 
183  WaitReady();
184 
185  if (!BlockRead(df_Read_BufferNum, df_Read_BufferIdx, pBuffer, n)) {
186  return false;
187  }
188  size -= n;
189  pBuffer = (void *)(n + (uintptr_t)pBuffer);
190 
191  df_Read_BufferIdx += n;
192 
193  if (df_Read_BufferIdx == df_PageSize) {
194  df_Read_PageAdr++;
196  df_Read_PageAdr = 1;
197  }
199 
200  // We are starting a new page - read FileNumber and FilePage
201  struct PageHeader ph;
202  if (!BlockRead(df_Read_BufferNum, 0, &ph, sizeof(ph))) {
203  return false;
204  }
205  df_FileNumber = ph.FileNumber;
206  df_FilePage = ph.FilePage;
207 
208  df_Read_BufferIdx = sizeof(ph);
209  }
210  }
211  return true;
212 }
213 
214 void DataFlash_Revo::SetFileNumber(uint16_t FileNumber)
215 {
216  df_FileNumber = FileNumber;
217  df_FilePage = 1;
218 }
219 
221 {
222  return df_FileNumber;
223 }
224 
226 {
227  return df_FilePage;
228 }
229 
231 {
232  log_write_started = false;
233 
234  ChipErase();
235 
236  // write the logging format in the last page
237  hal.scheduler->delay(100);
239  uint32_t version = DF_LOGGING_FORMAT;
240  log_write_started = true;
241  BlockWrite(df_BufferNum, 0, nullptr, 0, &version, sizeof(version));
242 
243  log_write_started = false;
244  FinishWrite();
245  hal.scheduler->delay(100);
246 
247 //[ just to test
248  StartRead(df_NumPages+1); // read last page after erase to check it
249 
250  StartRead(1);
251 //]
252 }
253 
254 bool DataFlash_Revo::NeedPrep(void)
255 {
256  return NeedErase();
257 }
258 
260 {
261  if (hal.util->get_soft_armed()) {
262  // do not want to do any filesystem operations while we are e.g. flying
263  return;
264  }
265  if (NeedErase()) {
266  EraseAll();
267  }
268 }
269 
270 /*
271  * we need to erase if the logging format has changed
272  */
273 bool DataFlash_Revo::NeedErase(void)
274 {
275  uint32_t version = 0;
276  StartRead(df_NumPages+1); // last page
277 
278  BlockRead(df_Read_BufferNum, 0, &version, sizeof(version));
279  StartRead(1);
280  if(version == DF_LOGGING_FORMAT) return false;
281 
282  printf("Need to erase: version is %lx required %lx\n", version, DF_LOGGING_FORMAT);
283 
284  return true;
285 }
286 
290 int16_t DataFlash_Revo::get_log_data_raw(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)
291 {
292  uint16_t data_page_size = df_PageSize - sizeof(struct PageHeader);
293 
294  if (offset >= data_page_size) {
295  page += offset / data_page_size;
296  offset = offset % data_page_size;
297  if (page > df_NumPages) {
298  // pages are one based, not zero
299  page = 1 + page - df_NumPages;
300  }
301  }
302  if (log_write_started || df_Read_PageAdr != page) {
303  StartRead(page);
304  }
305 
306  df_Read_BufferIdx = offset + sizeof(struct PageHeader);
307  if (!ReadBlock(data, len)) {
308  return -1;
309  }
310 
311  return (int16_t)len;
312 }
313 
317 int16_t DataFlash_Revo::get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)
318 {
319  if (offset == 0) {
320  uint8_t header[3];
321  get_log_data_raw(log_num, page, 0, 3, header);
322  adding_fmt_headers = (header[0] != HEAD_BYTE1 || header[1] != HEAD_BYTE2 || header[2] != LOG_FORMAT_MSG);
323  }
324  uint16_t ret = 0;
325 
326  if (adding_fmt_headers) {
327  // the log doesn't start with a FMT message, we need to add
328  // them
329  const uint16_t fmt_header_size = num_types() * sizeof(struct log_Format);
330  while (offset < fmt_header_size && len > 0) {
331  struct log_Format pkt;
332  uint8_t t = offset / sizeof(pkt);
333  uint8_t ofs = offset % sizeof(pkt);
334  Log_Fill_Format(structure(t), pkt);
335  uint8_t n = sizeof(pkt) - ofs;
336  if (n > len) {
337  n = len;
338  }
339  memcpy(data, ofs + (uint8_t *)&pkt, n);
340  data += n;
341  offset += n;
342  len -= n;
343  ret += n;
344  }
345  offset -= fmt_header_size;
346  }
347 
348  if (len > 0) {
349  ret += get_log_data_raw(log_num, page, offset, len, data);
350  }
351 
352  return ret;
353 }
354 
355 
356 // Public Methods //////////////////////////////////////////////////////////////
358 {
359 
360  df_NumPages=0;
361 
362 #if BOARD_DATAFLASH_ERASE_SIZE >= 65536
364 #else
366 #endif
368 
369  GPIO::_pinMode(DF_RESET,OUTPUT);
370  GPIO::_setSpeed(DF_RESET, GPIO_speed_100MHz);
371  // Reset the chip
373  Scheduler::_delay(1);
375 
376  _spi = hal.spi->get_device(HAL_DATAFLASH_NAME);
377 
378  if (!_spi) {
379  AP_HAL::panic("PANIC: DataFlash SPIDeviceDriver not found");
380  return; /* never reached */
381  }
382 
384  if (!_spi_sem) {
385  AP_HAL::panic("PANIC: DataFlash SPIDeviceDriver semaphore is null");
386  return; /* never reached */
387  }
388 
389 
390 
391  _spi_sem->take(10);
393 
395 
396  _spi_sem->give();
397 
398  df_NumPages = BOARD_DATAFLASH_PAGES - 1; // reserve last page for config information
399 
401 
403 
404  flash_died=false;
405 
406  log_write_started = true;
407 
409 
410 
411 
412 }
413 
415  if(flash_died) return;
416 
417  uint32_t t = AP_HAL::millis();
418  while(ReadStatus()!=0){
419 
420  Scheduler::yield(0); // пока ждем пусть другие работают
421 
422  if(AP_HAL::millis() - t > 4000) {
423  flash_died = true;
424  return;
425  }
426  }
427 }
428 
429 // try to take a semaphore safely from both in a timer and outside
430 bool DataFlash_Revo::_sem_take(uint8_t timeout)
431 {
432 
433  if(!_spi_sem || flash_died) return false;
434 
435  return _spi_sem->take(timeout);
436 }
437 
440  return false;
441 
443 
445  return true;
446 }
447 
450 
451  _spi_sem->give();
452 }
453 
454 
455 // This function is mainly to test the device
457 {
458  if (!cs_assert()) return;
459 
460  // Read manufacturer and ID command...
461  cmd[0] = JEDEC_DEVICE_ID;
462 
463  _spi->transfer(cmd, 1, buffer[1], 4);
464 
465  df_manufacturer = buffer[1][0];
466  df_device = (buffer[1][1] << 8) | buffer[1][2]; //capacity
467 
468  cs_release();
469 }
470 
471 bool DataFlash_Revo::getSectorCount(uint32_t *ptr){
472  uint8_t capacity = df_device & 0xFF;
473  uint8_t memtype = (df_device>>8) & 0xFF;
474  uint32_t size=0;
475 
476 
477  const char * mfg=NULL;
478 
479  switch(df_manufacturer){
480  case 0xEF: // Winbond Serial Flash
481  if (memtype == 0x40) {
482  mfg="Winbond";
483  size = (1 << ((capacity & 0x0f) + 8));
484 /*
485  const uint8_t _capID[11] = {0x10, 0x11, 0x12, 0x13, 0x14, 0x15, 0x16, 0x17, 0x18, 0x19, 0x43};
486  const uint32_t _memSize[11] = {64L*K, 128L*K, 256L*K, 512L*K, 1L*M, 2L*M, 4L*M, 8L*M, 16L*M, 32L*M, 8L*M};
487 */
488  erase_size=4096;
490  }
491  break;
492  case 0xbf: // SST
493  if (memtype == 0x25) {
494  mfg="Microchip";
495  size = (1 << ((capacity & 0x07) + 12));
496  }
497  break;
498 
499  case 0x20: // micron
500  if (memtype == 0xba){// JEDEC_ID_MICRON_N25Q128 0x20ba18
501  mfg="Micron";
502  size = (1 << ((capacity & 0x0f) + 8));
503  erase_size=4096;
505  } else if(memtype==0x20) { // JEDEC_ID_MICRON_M25P16 0x202015
506  mfg="Micron";
507  size = (1 << ((capacity & 0x0f) + 8));
508  }
509  break;
510 
511  case 0xC2: //JEDEC_ID_MACRONIX_MX25L6406E 0xC22017
512  if (memtype == 0x20) {
513  mfg="MACRONIX";
514  size = (1 << ((capacity & 0x0f) + 8));
515  erase_size=4096;
517  }
518  break;
519 
520  case 0x9D: // ISSI
521  if (memtype == 0x40 || memtype == 0x30) {
522  mfg = "ISSI";
523  size = (1 << ((capacity & 0x0f) + 8));
524  }
525  break;
526 
527  default:
528  break;
529  }
530 
531  if(mfg && size) {
532  printf("%s SPI Flash found sectors=%ld\n", mfg, size);
533  }else {
534  printf("\nUnknown Flash! SPI Flash codes: mfg=%x type=%x cap=%x\n ",df_manufacturer, memtype, capacity);
535  size = BOARD_DATAFLASH_PAGES; // as defined
536  }
537 
538 
540 
541  size -= (erase_size/DF_PAGE_SIZE); // reserve last page for config information
542 
543  *ptr = size; // in 256b blocks
544 
545  return true;
546 
547 }
548 
549 // Read the status register
551 {
552  uint8_t tmp;
553 
554  // activate dataflash command decoder
555  if (!cs_assert()) return JEDEC_STATUS_BUSY;
556 
557  // Read status command
558 #if 0
560  tmp = spi_read(); // We only want to extract the READY/BUSY bit
561 #else
562  cmd[0] = JEDEC_READ_STATUS;
563 
564  _spi->transfer(cmd, 1, &cmd[1], 1);
565  tmp = cmd[1];
566 #endif
567  // release SPI bus for use by other sensors
568  cs_release();
569 
570  return tmp;
571 }
572 
574 {
575  // We only want to extract the READY/BUSY bit
576  int32_t status = ReadStatusReg();
577  if (status < 0)
578  return -1;
579  return status & JEDEC_STATUS_BUSY;
580 }
581 
582 
583 void DataFlash_Revo::PageToBuffer(unsigned char BufferNum, uint16_t pageNum)
584 {
585 
586  uint32_t PageAdr = pageNum * DF_PAGE_SIZE;
587 
588  if (!cs_assert()) return;
589 
590  cmd[0] = JEDEC_READ_DATA;
591  cmd[1] = (PageAdr >> 16) & 0xff;
592  cmd[2] = (PageAdr >> 8) & 0xff;
593  cmd[3] = (PageAdr >> 0) & 0xff;
594 
595  _spi->transfer(cmd, 4, buffer[BufferNum], DF_PAGE_SIZE);
596 
597  cs_release();
598 }
599 
600 void DataFlash_Revo::BufferToPage (unsigned char BufferNum, uint16_t pageNum, unsigned char wait)
601 {
602  uint32_t PageAdr = pageNum * DF_PAGE_SIZE;
603 
605 
606  if (!cs_assert()) return;
607 
608  cmd[0] = JEDEC_PAGE_WRITE;
609  cmd[1] = (PageAdr >> 16) & 0xff;
610  cmd[2] = (PageAdr >> 8) & 0xff;
611  cmd[3] = (PageAdr >> 0) & 0xff;
612 
613  _spi->transfer(cmd, 4,NULL, 0);
614 
615  _spi->transfer(buffer[BufferNum], DF_PAGE_SIZE, NULL, 0);
616 
617  cs_release();
618 
619  if(wait) WaitReady();
620 
621 }
622 
623 void DataFlash_Revo::BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data)
624 {
625  buffer[BufferNum][IntPageAdr] = (uint8_t)Data;
626 }
627 
628 void DataFlash_Revo::BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr,
629  const void *pHeader, uint8_t hdr_size,
630  const void *pBuffer, uint16_t size)
631 {
632  if (hdr_size) {
633  memcpy(&buffer[BufferNum][IntPageAdr],
634  pHeader,
635  hdr_size);
636  }
637  memcpy(&buffer[BufferNum][IntPageAdr+hdr_size],
638  pBuffer,
639  size);
640 }
641 
642 // read size bytes of data to a page. The caller must ensure that
643 // the data fits within the page, otherwise it will wrap to the
644 // start of the page
645 bool DataFlash_Revo::BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size)
646 {
647  memcpy(pBuffer, &buffer[BufferNum][IntPageAdr], size);
648  return true;
649 }
650 
651 /*
652 
653 * 2 097 152 bytes (8 bits each)
654 * 32 sectors (512 Kbits, 65536 bytes each)
655 * 8192 pages (256 bytes each).
656 
657 */
658 
659 void DataFlash_Revo::PageErase (uint16_t pageNum)
660 {
661 
662  uint32_t PageAdr = pageNum * DF_PAGE_SIZE;
663 
664  cmd[0] = erase_cmd;
665  cmd[1] = (PageAdr >> 16) & 0xff;
666  cmd[2] = (PageAdr >> 8) & 0xff;
667  cmd[3] = (PageAdr >> 0) & 0xff;
668 
670 
671  if (!cs_assert()) return;
672 
673  _spi->transfer(cmd, 4, NULL, 0);
674 
675  cs_release();
676 }
677 
678 
680 {
681 
682  cmd[0] = JEDEC_BULK_ERASE;
683 
685 
686  if (!cs_assert()) return;
687 
688  _spi->transfer(cmd, 1, NULL, 0);
689 
690  cs_release();
691 }
692 
693 
695 {
696  // activate dataflash command decoder
697  if (!cs_assert()) return;
698 
700 
701  cs_release();
702 }
703 
705 
706 // This function determines the number of whole or partial log files in the DataFlash
707 // Wholly overwritten files are (of course) lost.
708 uint16_t DataFlash_Revo::get_num_logs(void)
709 {
710  uint16_t lastpage;
711  uint16_t last;
712  uint16_t first;
713 
714  if (find_last_page() == 1) {
715  return 0;
716  }
717 
718  StartRead(1);
719 
720  if (GetFileNumber() == 0xFFFF) {
721  return 0;
722  }
723 
724  lastpage = find_last_page();
725  StartRead(lastpage);
726  last = GetFileNumber();
727  StartRead(lastpage + 2);
728  if (GetFileNumber() == 0xFFFF)
729  StartRead(((lastpage >> 8) + 1) << 8); // next sector
730  first = GetFileNumber();
731  if(first > last) {
732  StartRead(1);
733  first = GetFileNumber();
734  }
735 
736  if (last == first) {
737  return 1;
738  }
739 
740  return (last - first + 1);
741 }
742 
743 
744 // This function starts a new log file in the DataFlash
745 uint16_t DataFlash_Revo::start_new_log(void)
746 {
747  uint16_t last_page = find_last_page();
748 
749  StartRead(last_page);
750  //Serial.print("last page: "); Serial.println(last_page);
751  //Serial.print("file #: "); Serial.println(GetFileNumber());
752  //Serial.print("file page: "); Serial.println(GetFilePage());
753 
754  if(find_last_log() == 0 || GetFileNumber() == 0xFFFF) {
755  SetFileNumber(1);
756  StartWrite(1);
757  //Serial.println("start log from 0");
758  log_write_started = true;
759  return 1;
760  }
761 
762  uint16_t new_log_num;
763 
764  // Check for log of length 1 page and suppress
765  if(GetFilePage() <= 1) {
766  new_log_num = GetFileNumber();
767  // Last log too short, reuse its number
768  // and overwrite it
769  SetFileNumber(new_log_num);
770  StartWrite(last_page);
771  } else {
772  new_log_num = GetFileNumber()+1;
773  if (last_page == 0xFFFF) {
774  last_page=0;
775  }
776  SetFileNumber(new_log_num);
777  StartWrite(last_page + 1);
778  }
779  log_write_started = true;
780  return new_log_num;
781 }
782 
783 // This function finds the first and last pages of a log file
784 // The first page may be greater than the last page if the DataFlash has been filled and partially overwritten.
785 void DataFlash_Revo::get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page)
786 {
787  uint16_t num = get_num_logs();
788  uint16_t look;
789 
790  if (df_BufferIdx != 0) {
791  FinishWrite();
792  hal.scheduler->delay(100);
793  }
794 
795  if(num == 1)
796  {
798  if (GetFileNumber() == 0xFFFF)
799  {
800  start_page = 1;
801  end_page = find_last_page_of_log((uint16_t)log_num);
802  } else {
803  end_page = find_last_page_of_log((uint16_t)log_num);
804  start_page = end_page + 1;
805  }
806 
807  } else {
808  if(log_num==1) {
810  if(GetFileNumber() == 0xFFFF) {
811  start_page = 1;
812  } else {
813  start_page = find_last_page() + 1;
814  }
815  } else {
816  if(log_num == find_last_log() - num + 1) {
817  start_page = find_last_page() + 1;
818  } else {
819  look = log_num-1;
820  do {
821  start_page = find_last_page_of_log(look) + 1;
822  look--;
823  } while (start_page <= 0 && look >=1);
824  }
825  }
826  }
827  if (start_page == df_NumPages+1 || start_page == 0) {
828  start_page = 1;
829  }
830  end_page = find_last_page_of_log(log_num);
831  if (end_page == 0) {
832  end_page = start_page;
833  }
834 
835 
836 }
837 
839 {
841  if(GetFileNumber() == 0xFFFF)
842  return 0;
843  else
844  return 1;
845 }
846 
847 
848 // This funciton finds the last log number
849 uint16_t DataFlash_Revo::find_last_log(void)
850 {
851  uint16_t last_page = find_last_page();
852  StartRead(last_page);
853  return GetFileNumber();
854 }
855 
856 // This function finds the last page of the last file
857 uint16_t DataFlash_Revo::find_last_page(void)
858 {
859  uint16_t look;
860  uint16_t bottom = 1;
861  uint16_t top = df_NumPages;
862  uint32_t look_hash;
863  uint32_t bottom_hash;
864  uint32_t top_hash;
865 
866  StartRead(bottom);
867  bottom_hash = ((int32_t)GetFileNumber()<<16) | GetFilePage();
868 
869  while(top-bottom > 1) {
870  look = (top+bottom)/2;
871  StartRead(look);
872  look_hash = (int32_t)GetFileNumber()<<16 | GetFilePage();
873  if (look_hash >= 0xFFFF0000) look_hash = 0;
874 
875  if(look_hash < bottom_hash) {
876  // move down
877  top = look;
878  } else {
879  // move up
880  bottom = look;
881  bottom_hash = look_hash;
882  }
883  }
884 
885  StartRead(top);
886  top_hash = ((int32_t)GetFileNumber()<<16) | GetFilePage();
887  if (top_hash >= 0xFFFF0000) {
888  top_hash = 0;
889  }
890  if (top_hash > bottom_hash) {
891  return top;
892  }
893 
894  return bottom;
895 }
896 
897 // This function finds the last page of a particular log file
898 uint16_t DataFlash_Revo::find_last_page_of_log(uint16_t log_number)
899 {
900  uint16_t look;
901  uint16_t bottom;
902  uint16_t top;
903  uint32_t look_hash;
904  uint32_t check_hash;
905 
906  if(check_wrapped()) {
907  StartRead(1);
908  bottom = GetFileNumber();
909  if (bottom > log_number)
910  {
911  bottom = find_last_page();
912  top = df_NumPages;
913  } else {
914  bottom = 1;
915  top = find_last_page();
916  }
917  } else {
918  bottom = 1;
919  top = find_last_page();
920  }
921 
922  check_hash = (int32_t)log_number<<16 | 0xFFFF;
923 
924  while(top-bottom > 1)
925  {
926  look = (top+bottom)/2;
927  StartRead(look);
928  look_hash = (int32_t)GetFileNumber()<<16 | GetFilePage();
929  if (look_hash >= 0xFFFF0000) look_hash = 0;
930 
931  if(look_hash > check_hash) {
932  // move down
933  top = look;
934  } else {
935  // move up
936  bottom = look;
937  }
938  }
939 
940  StartRead(top);
941  if (GetFileNumber() == log_number) return top;
942 
943  StartRead(bottom);
944  if (GetFileNumber() == log_number) return bottom;
945 
946  return -1;
947 }
948 
949 
950 void DataFlash_Revo::get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc)
951 {
952  uint16_t start, end;
953  get_log_boundaries(log_num, start, end);
954  if (end >= start) {
955  size = (end + 1 - start) * (uint32_t)df_PageSize;
956  } else {
957  size = (df_NumPages + end - start) * (uint32_t)df_PageSize;
958  }
959  time_utc = 0;
960 }
961 #endif
int printf(const char *fmt,...)
Definition: stdio.c:113
bool get_soft_armed() const
Definition: Util.h:15
uint16_t df_FilePage
uint8_t df_manufacturer
uint8_t num_types() const
bool getSectorCount(uint32_t *ptr)
uint16_t GetPage(void)
uint16_t df_Read_PageAdr
#define JEDEC_PAGE_WRITE
static AP_HAL::OwnPtr< AP_HAL::SPIDevice > _spi
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
#define DF_PAGE_SIZE
virtual void Init()
static AP_HAL::Semaphore * _spi_sem
uint16_t GetWritePage(void)
uint32_t df_NumPages
#define JEDEC_STATUS_BUSY
uint16_t GetFileNumber()
AP_HAL::Util * util
Definition: HAL.h:115
void get_log_boundaries(uint16_t log_num, uint16_t &start_page, uint16_t &end_page)
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
#define BOARD_DATAFLASH_PAGES
Definition: board.h:138
Definition: GPIO.h:35
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
bool WritesOK() const override
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
#define DF_RESET
void FinishWrite(void)
const struct LogStructure * structure(uint8_t structure) const
uint16_t last_block_num
bool BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size)
#define JEDEC_WRITE_ENABLE
uint32_t bufferspace_available()
static bool flash_died
#define BOARD_DATAFLASH_ERASE_SIZE
Definition: board.h:139
#define JEDEC_READ_DATA
uint32_t erase_size
virtual void delay(uint16_t ms)=0
uint16_t df_BufferIdx
#define HEAD_BYTE1
Definition: LogStructure.h:13
void yield(uint32_t us)
Definition: system.cpp:99
virtual OwnPtr< SPIDevice > get_device(const char *name)
Definition: SPIDevice.h:68
uint8_t ReadStatusReg()
int _write(int fd, const char *buf, size_t cnt)
Definition: syscalls.c:191
virtual Semaphore * get_semaphore() override=0
uint8_t df_BufferNum
bool CardInserted(void) const
virtual bool WriteBlockCheckStartupMessages()
uint16_t GetFilePage()
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc)
#define JEDEC_SECTOR_ERASE
uint32_t millis()
Definition: system.cpp:157
void spi_write(uint8_t b)
void StartRead(uint16_t PageAdr)
bool NeedErase(void)
uint16_t get_num_logs() override
#define JEDEC_BULK_ERASE
uint16_t df_device
#define JEDEC_PAGE_ERASE
virtual bool give()=0
int16_t get_log_data_raw(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)
AP_HAL::SPIDeviceManager * spi
Definition: HAL.h:107
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)
void ReadManufacturerID()
#define NULL
Definition: hal_types.h:59
uint16_t df_PageAdr
virtual bool set_speed(Device::Speed speed) override=0
void BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr, const void *pHeader, uint8_t hdr_size, const void *pBuffer, uint16_t size)
void BufferWrite(uint8_t BufferNum, uint16_t IntPageAdr, uint8_t Data)
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
void Log_Fill_Format(const struct LogStructure *structure, struct log_Format &pkt)
Definition: LogFile.cpp:29
void PageToBuffer(uint8_t BufferNum, uint16_t PageAdr)
bool ReadBlock(void *pBuffer, uint16_t size)
void Flash_Jedec_WriteEnable()
void StartWrite(uint16_t PageAdr)
static uint16_t log_num
uint8_t df_Read_BufferNum
static bool _sem_take(uint8_t timeout)
uint16_t find_last_page_of_log(uint16_t log_number)
void BufferToPage(uint8_t BufferNum, uint16_t PageAdr, uint8_t wait)
#define JEDEC_READ_STATUS
uint16_t df_Read_BufferIdx
uint16_t find_last_page(void)
bool NeedPrep(void)
uint16_t find_last_log() override
uint16_t df_PageSize
uint16_t df_FileNumber
#define JEDEC_DEVICE_ID
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
uint16_t start_new_log(void)
void uint32_t num
Definition: systick.h:80
void PageErase(uint16_t PageAdr)
bool _WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
uint8_t ReadStatus()
bool check_wrapped(void)
void Init() override
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
static bool log_write_started
void SetFileNumber(uint16_t FileNumber)
#define HEAD_BYTE2
Definition: LogStructure.h:14