AP_Logger_DataFlash.cpp 7.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314
  1. /*
  2. logging to a DataFlash block based storage device on SPI
  3. */
  4. #include <AP_HAL/AP_HAL.h>
  5. #ifdef HAL_LOGGING_DATAFLASH
  6. #include "AP_Logger_DataFlash.h"
  7. #include <stdio.h>
  8. extern const AP_HAL::HAL& hal;
  9. #define JEDEC_WRITE_ENABLE 0x06
  10. #define JEDEC_WRITE_DISABLE 0x04
  11. #define JEDEC_READ_STATUS 0x05
  12. #define JEDEC_WRITE_STATUS 0x01
  13. #define JEDEC_READ_DATA 0x03
  14. #define JEDEC_FAST_READ 0x0b
  15. #define JEDEC_DEVICE_ID 0x9F
  16. #define JEDEC_PAGE_WRITE 0x02
  17. #define JEDEC_BULK_ERASE 0xC7
  18. #define JEDEC_SECTOR4_ERASE 0x20 // 4k erase
  19. #define JEDEC_BLOCK32_ERASE 0x52 // 32K erase
  20. #define JEDEC_BLOCK64_ERASE 0xD8 // 64K erase
  21. #define JEDEC_STATUS_BUSY 0x01
  22. #define JEDEC_STATUS_WRITEPROTECT 0x02
  23. #define JEDEC_STATUS_BP0 0x04
  24. #define JEDEC_STATUS_BP1 0x08
  25. #define JEDEC_STATUS_BP2 0x10
  26. #define JEDEC_STATUS_TP 0x20
  27. #define JEDEC_STATUS_SEC 0x40
  28. #define JEDEC_STATUS_SRP0 0x80
  29. /*
  30. flash device IDs taken from betaflight flash_m25p16.c
  31. Format is manufacturer, memory type, then capacity
  32. */
  33. #define JEDEC_ID_MACRONIX_MX25L3206E 0xC22016
  34. #define JEDEC_ID_MACRONIX_MX25L6406E 0xC22017
  35. #define JEDEC_ID_MACRONIX_MX25L25635E 0xC22019
  36. #define JEDEC_ID_MICRON_M25P16 0x202015
  37. #define JEDEC_ID_MICRON_N25Q064 0x20BA17
  38. #define JEDEC_ID_MICRON_N25Q128 0x20ba18
  39. #define JEDEC_ID_WINBOND_W25Q16 0xEF4015
  40. #define JEDEC_ID_WINBOND_W25Q32 0xEF4016
  41. #define JEDEC_ID_WINBOND_W25Q64 0xEF4017
  42. #define JEDEC_ID_WINBOND_W25Q128 0xEF4018
  43. #define JEDEC_ID_WINBOND_W25Q256 0xEF4019
  44. #define JEDEC_ID_CYPRESS_S25FL128L 0x016018
  45. void AP_Logger_DataFlash::Init()
  46. {
  47. dev = hal.spi->get_device("dataflash");
  48. if (!dev) {
  49. AP_HAL::panic("PANIC: AP_Logger SPIDeviceDriver not found");
  50. return;
  51. }
  52. dev_sem = dev->get_semaphore();
  53. if (!getSectorCount()) {
  54. flash_died = true;
  55. return;
  56. }
  57. if (use_32bit_address) {
  58. Enter4ByteAddressMode();
  59. }
  60. flash_died = false;
  61. AP_Logger_Block::Init();
  62. //flash_test();
  63. }
  64. /*
  65. wait for busy flag to be cleared
  66. */
  67. void AP_Logger_DataFlash::WaitReady()
  68. {
  69. if (flash_died) {
  70. return;
  71. }
  72. uint32_t t = AP_HAL::millis();
  73. while (Busy()) {
  74. hal.scheduler->delay_microseconds(100);
  75. if (AP_HAL::millis() - t > 5000) {
  76. printf("DataFlash: flash_died\n");
  77. flash_died = true;
  78. break;
  79. }
  80. }
  81. }
  82. bool AP_Logger_DataFlash::getSectorCount(void)
  83. {
  84. WaitReady();
  85. WITH_SEMAPHORE(dev_sem);
  86. // Read manufacturer ID
  87. uint8_t cmd = JEDEC_DEVICE_ID;
  88. dev->transfer(&cmd, 1, buffer, 4);
  89. uint32_t id = buffer[0] << 16 | buffer[1] << 8 | buffer[2];
  90. uint32_t sectors = 0;
  91. switch (id) {
  92. case JEDEC_ID_WINBOND_W25Q16:
  93. case JEDEC_ID_MICRON_M25P16:
  94. sectors = 32;
  95. df_PagePerSector = 256;
  96. break;
  97. case JEDEC_ID_WINBOND_W25Q32:
  98. case JEDEC_ID_MACRONIX_MX25L3206E:
  99. sectors = 64;
  100. df_PagePerSector = 256;
  101. break;
  102. case JEDEC_ID_MICRON_N25Q064:
  103. case JEDEC_ID_WINBOND_W25Q64:
  104. case JEDEC_ID_MACRONIX_MX25L6406E:
  105. sectors = 128;
  106. df_PagePerSector = 256;
  107. break;
  108. case JEDEC_ID_MICRON_N25Q128:
  109. case JEDEC_ID_WINBOND_W25Q128:
  110. case JEDEC_ID_CYPRESS_S25FL128L:
  111. sectors = 256;
  112. df_PagePerSector = 256;
  113. break;
  114. case JEDEC_ID_WINBOND_W25Q256:
  115. case JEDEC_ID_MACRONIX_MX25L25635E:
  116. sectors = 512;
  117. df_PagePerSector = 256;
  118. use_32bit_address = true;
  119. break;
  120. default:
  121. hal.scheduler->delay(2000);
  122. printf("Unknown SPI Flash 0x%08x\n", id);
  123. return false;
  124. }
  125. df_PageSize = 256;
  126. df_NumPages = sectors * df_PagePerSector;
  127. erase_cmd = JEDEC_BLOCK64_ERASE;
  128. hal.scheduler->delay(2000);
  129. printf("SPI Flash 0x%08x found pages=%u erase=%uk\n",
  130. id, df_NumPages, (df_PagePerSector * (uint32_t)df_PageSize)/1024);
  131. return true;
  132. }
  133. // Read the status register
  134. uint8_t AP_Logger_DataFlash::ReadStatusReg()
  135. {
  136. WITH_SEMAPHORE(dev_sem);
  137. uint8_t cmd = JEDEC_READ_STATUS;
  138. uint8_t status;
  139. dev->transfer(&cmd, 1, &status, 1);
  140. return status;
  141. }
  142. bool AP_Logger_DataFlash::Busy()
  143. {
  144. int32_t status = ReadStatusReg();
  145. if (status < 0) {
  146. return true;
  147. }
  148. return (status & JEDEC_STATUS_BUSY) != 0;
  149. }
  150. void AP_Logger_DataFlash::Enter4ByteAddressMode(void)
  151. {
  152. WITH_SEMAPHORE(dev_sem);
  153. const uint8_t cmd = 0xB7;
  154. dev->transfer(&cmd, 1, NULL, 0);
  155. }
  156. /*
  157. send a command with an address
  158. */
  159. void AP_Logger_DataFlash::send_command_addr(uint8_t command, uint32_t PageAdr)
  160. {
  161. uint8_t cmd[5];
  162. cmd[0] = command;
  163. if (use_32bit_address) {
  164. cmd[1] = (PageAdr >> 24) & 0xff;
  165. cmd[2] = (PageAdr >> 16) & 0xff;
  166. cmd[3] = (PageAdr >> 8) & 0xff;
  167. cmd[4] = (PageAdr >> 0) & 0xff;
  168. } else {
  169. cmd[1] = (PageAdr >> 16) & 0xff;
  170. cmd[2] = (PageAdr >> 8) & 0xff;
  171. cmd[3] = (PageAdr >> 0) & 0xff;
  172. }
  173. dev->transfer(cmd, use_32bit_address?5:4, NULL, 0);
  174. }
  175. void AP_Logger_DataFlash::PageToBuffer(uint32_t pageNum)
  176. {
  177. if (pageNum == 0 || pageNum > df_NumPages+1) {
  178. printf("Invalid page read %u\n", pageNum);
  179. memset(buffer, 0xFF, df_PageSize);
  180. return;
  181. }
  182. WaitReady();
  183. uint32_t PageAdr = (pageNum-1) * df_PageSize;
  184. WITH_SEMAPHORE(dev_sem);
  185. dev->set_chip_select(true);
  186. send_command_addr(JEDEC_READ_DATA, PageAdr);
  187. dev->transfer(NULL, 0, buffer, df_PageSize);
  188. dev->set_chip_select(false);
  189. }
  190. void AP_Logger_DataFlash::BufferToPage(uint32_t pageNum)
  191. {
  192. if (pageNum == 0 || pageNum > df_NumPages+1) {
  193. printf("Invalid page write %u\n", pageNum);
  194. return;
  195. }
  196. WriteEnable();
  197. WITH_SEMAPHORE(dev_sem);
  198. uint32_t PageAdr = (pageNum-1) * df_PageSize;
  199. dev->set_chip_select(true);
  200. send_command_addr(JEDEC_PAGE_WRITE, PageAdr);
  201. dev->transfer(buffer, df_PageSize, NULL, 0);
  202. dev->set_chip_select(false);
  203. }
  204. /*
  205. erase one sector (sizes varies with hw)
  206. */
  207. void AP_Logger_DataFlash::SectorErase(uint32_t sectorNum)
  208. {
  209. WriteEnable();
  210. WITH_SEMAPHORE(dev_sem);
  211. uint32_t PageAdr = sectorNum * df_PageSize * df_PagePerSector;
  212. send_command_addr(erase_cmd, PageAdr);
  213. }
  214. void AP_Logger_DataFlash::StartErase()
  215. {
  216. WriteEnable();
  217. WITH_SEMAPHORE(dev_sem);
  218. uint8_t cmd = JEDEC_BULK_ERASE;
  219. dev->transfer(&cmd, 1, NULL, 0);
  220. erase_start_ms = AP_HAL::millis();
  221. printf("Dataflash: erase started\n");
  222. }
  223. bool AP_Logger_DataFlash::InErase()
  224. {
  225. if (erase_start_ms && !Busy()) {
  226. printf("Dataflash: erase done (%u ms)\n", AP_HAL::millis() - erase_start_ms);
  227. erase_start_ms = 0;
  228. }
  229. return erase_start_ms != 0;
  230. }
  231. void AP_Logger_DataFlash::WriteEnable(void)
  232. {
  233. WaitReady();
  234. WITH_SEMAPHORE(dev_sem);
  235. uint8_t b = JEDEC_WRITE_ENABLE;
  236. dev->transfer(&b, 1, NULL, 0);
  237. }
  238. void AP_Logger_DataFlash::flash_test()
  239. {
  240. for (uint8_t i=1; i<=20; i++) {
  241. printf("Flash fill %u\n", i);
  242. if (i % df_PagePerSector == 0) {
  243. SectorErase(i / df_PagePerSector);
  244. }
  245. memset(buffer, i, df_PageSize);
  246. BufferToPage(i);
  247. }
  248. for (uint8_t i=1; i<=20; i++) {
  249. printf("Flash check %u\n", i);
  250. PageToBuffer(i);
  251. for (uint16_t j=0; j<df_PageSize; j++) {
  252. if (buffer[j] != i) {
  253. printf("Test error: page %u j=%u v=%u\n", i, j, buffer[j]);
  254. break;
  255. }
  256. }
  257. }
  258. }
  259. #endif // HAL_LOGGING_DATAFLASH