Storage.cpp 7.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292
  1. #include <AP_HAL/AP_HAL.h>
  2. #include <assert.h>
  3. #include <sys/types.h>
  4. #include <sys/stat.h>
  5. #include <fcntl.h>
  6. #include <unistd.h>
  7. #include "Storage.h"
  8. #include <stdio.h>
  9. using namespace HALSITL;
  10. extern const AP_HAL::HAL& hal;
  11. void Storage::_storage_open(void)
  12. {
  13. if (_initialised) {
  14. return;
  15. }
  16. #if STORAGE_USE_POSIX
  17. // if we have failed filesystem init don't try again
  18. if (log_fd == -1) {
  19. return;
  20. }
  21. #endif
  22. _dirty_mask.clearall();
  23. #if STORAGE_USE_FLASH
  24. // load from storage backend
  25. _flash_load();
  26. #elif STORAGE_USE_POSIX
  27. log_fd = open(HAL_STORAGE_FILE, O_RDWR|O_CREAT, 0644);
  28. if (log_fd == -1) {
  29. hal.console->printf("open failed of " HAL_STORAGE_FILE "\n");
  30. return;
  31. }
  32. int ret = read(log_fd, _buffer, HAL_STORAGE_SIZE);
  33. if (ret < 0) {
  34. hal.console->printf("read failed for " HAL_STORAGE_FILE "\n");
  35. close(log_fd);
  36. log_fd = -1;
  37. return;
  38. }
  39. // pre-fill to full size
  40. if (lseek(log_fd, ret, SEEK_SET) != ret ||
  41. write(log_fd, &_buffer[ret], HAL_STORAGE_SIZE-ret) != HAL_STORAGE_SIZE-ret) {
  42. hal.console->printf("setup failed for " HAL_STORAGE_FILE "\n");
  43. close(log_fd);
  44. log_fd = -1;
  45. return;
  46. }
  47. using_filesystem = true;
  48. #else
  49. #error "No storage system enabled"
  50. #endif
  51. _initialised = true;
  52. }
  53. /*
  54. mark some lines as dirty. Note that there is no attempt to avoid
  55. the race condition between this code and the _timer_tick() code
  56. below, which both update _dirty_mask. If we lose the race then the
  57. result is that a line is written more than once, but it won't result
  58. in a line not being written.
  59. */
  60. void Storage::_mark_dirty(uint16_t loc, uint16_t length)
  61. {
  62. uint16_t end = loc + length;
  63. for (uint16_t line=loc>>STORAGE_LINE_SHIFT;
  64. line <= end>>STORAGE_LINE_SHIFT;
  65. line++) {
  66. _dirty_mask.set(line);
  67. }
  68. }
  69. void Storage::read_block(void *dst, uint16_t loc, size_t n)
  70. {
  71. if (loc >= sizeof(_buffer)-(n-1)) {
  72. return;
  73. }
  74. _storage_open();
  75. memcpy(dst, &_buffer[loc], n);
  76. }
  77. void Storage::write_block(uint16_t loc, const void *src, size_t n)
  78. {
  79. if (loc >= sizeof(_buffer)-(n-1)) {
  80. return;
  81. }
  82. if (memcmp(src, &_buffer[loc], n) != 0) {
  83. _storage_open();
  84. memcpy(&_buffer[loc], src, n);
  85. _mark_dirty(loc, n);
  86. }
  87. }
  88. void Storage::_timer_tick(void)
  89. {
  90. if (!_initialised) {
  91. return;
  92. }
  93. if (_dirty_mask.empty()) {
  94. _last_empty_ms = AP_HAL::millis();
  95. return;
  96. }
  97. // write out the first dirty line. We don't write more
  98. // than one to keep the latency of this call to a minimum
  99. uint16_t i;
  100. for (i=0; i<STORAGE_NUM_LINES; i++) {
  101. if (_dirty_mask.get(i)) {
  102. break;
  103. }
  104. }
  105. if (i == STORAGE_NUM_LINES) {
  106. // this shouldn't be possible
  107. return;
  108. }
  109. #if STORAGE_USE_POSIX
  110. if (using_filesystem && log_fd != -1) {
  111. const off_t offset = STORAGE_LINE_SIZE*i;
  112. if (lseek(log_fd, offset, SEEK_SET) != offset) {
  113. return;
  114. }
  115. if (write(log_fd, &_buffer[offset], STORAGE_LINE_SIZE) != STORAGE_LINE_SIZE) {
  116. return;
  117. }
  118. _dirty_mask.clear(i);
  119. return;
  120. }
  121. #endif
  122. #if STORAGE_USE_FLASH
  123. // save to storage backend
  124. _flash_write(i);
  125. #endif
  126. }
  127. /*
  128. load all data from flash
  129. */
  130. void Storage::_flash_load(void)
  131. {
  132. #if STORAGE_USE_FLASH
  133. if (!_flash.init()) {
  134. AP_HAL::panic("unable to init flash storage");
  135. }
  136. #else
  137. AP_HAL::panic("unable to init storage");
  138. #endif
  139. }
  140. /*
  141. write one storage line. This also updates _dirty_mask.
  142. */
  143. void Storage::_flash_write(uint16_t line)
  144. {
  145. #if STORAGE_USE_FLASH
  146. if (_flash.write(line*STORAGE_LINE_SIZE, STORAGE_LINE_SIZE)) {
  147. // mark the line clean
  148. _dirty_mask.clear(line);
  149. }
  150. #endif
  151. }
  152. #if STORAGE_USE_FLASH
  153. /*
  154. emulate writing to flash
  155. */
  156. static int flash_fd = -1;
  157. static uint32_t sitl_flash_getpageaddr(uint32_t page)
  158. {
  159. return page * HAL_STORAGE_SIZE;
  160. }
  161. static void sitl_flash_open(void)
  162. {
  163. if (flash_fd == -1) {
  164. flash_fd = open("flash.dat", O_RDWR, 0644);
  165. if (flash_fd == -1) {
  166. flash_fd = open("flash.dat", O_RDWR|O_CREAT, 0644);
  167. if (flash_fd == -1) {
  168. AP_HAL::panic("Failed to open flash.dat");
  169. }
  170. if (ftruncate(flash_fd, 2*HAL_STORAGE_SIZE) != 0) {
  171. AP_HAL::panic("Failed to create flash.dat");
  172. }
  173. uint8_t fill[HAL_STORAGE_SIZE*2];
  174. memset(fill, 0xff, sizeof(fill));
  175. pwrite(flash_fd, fill, sizeof(fill), 0);
  176. }
  177. }
  178. }
  179. static bool sitl_flash_write(uint32_t addr, const uint8_t *data, uint32_t length)
  180. {
  181. sitl_flash_open();
  182. uint8_t old[length];
  183. if (pread(flash_fd, old, length, addr) != length) {
  184. AP_HAL::panic("Failed to read flash.dat");
  185. }
  186. // check that we are only ever clearing bits (real flash storage can only ever clear bits,
  187. // except for an erase
  188. for (uint32_t i=0; i<length; i++) {
  189. if (data[i] & ~old[i]) {
  190. AP_HAL::panic("Attempt to set flash byte 0x%02x from 0x%02x at %u\n", data[i], old[i], addr+i);
  191. }
  192. }
  193. return pwrite(flash_fd, data, length, addr) == length;
  194. }
  195. static bool sitl_flash_read(uint32_t addr, uint8_t *data, uint32_t length)
  196. {
  197. sitl_flash_open();
  198. return pread(flash_fd, data, length, addr) == length;
  199. }
  200. static bool sitl_flash_erasepage(uint32_t page)
  201. {
  202. uint8_t fill[HAL_STORAGE_SIZE];
  203. memset(fill, 0xff, sizeof(fill));
  204. sitl_flash_open();
  205. bool ret = pwrite(flash_fd, fill, sizeof(fill), page * HAL_STORAGE_SIZE) == sizeof(fill);
  206. printf("erase %u -> %u\n", page, ret);
  207. return ret;
  208. }
  209. /*
  210. callback to write data to flash
  211. */
  212. bool Storage::_flash_write_data(uint8_t sector, uint32_t offset, const uint8_t *data, uint16_t length)
  213. {
  214. size_t base_address = sitl_flash_getpageaddr(sector);
  215. bool ret = sitl_flash_write(base_address+offset, data, length);
  216. if (!ret && _flash_erase_ok()) {
  217. // we are getting flash write errors while disarmed. Try
  218. // re-writing all of flash
  219. uint32_t now = AP_HAL::millis();
  220. if (now - _last_re_init_ms > 5000) {
  221. _last_re_init_ms = now;
  222. bool ok = _flash.re_initialise();
  223. hal.console->printf("Storage: failed at %u:%u for %u - re-init %u\n",
  224. (unsigned)sector, (unsigned)offset, (unsigned)length, (unsigned)ok);
  225. }
  226. }
  227. return ret;
  228. }
  229. /*
  230. callback to read data from flash
  231. */
  232. bool Storage::_flash_read_data(uint8_t sector, uint32_t offset, uint8_t *data, uint16_t length)
  233. {
  234. size_t base_address = sitl_flash_getpageaddr(sector);
  235. return sitl_flash_read(base_address+offset, data, length);
  236. }
  237. /*
  238. callback to erase flash sector
  239. */
  240. bool Storage::_flash_erase_sector(uint8_t sector)
  241. {
  242. return sitl_flash_erasepage(sector);
  243. }
  244. /*
  245. callback to check if erase is allowed
  246. */
  247. bool Storage::_flash_erase_ok(void)
  248. {
  249. // only allow erase while disarmed
  250. return !hal.util->get_soft_armed();
  251. }
  252. #endif // STORAGE_USE_FLASH
  253. /*
  254. consider storage healthy if we have nothing to write sometime in the
  255. last 2 seconds
  256. */
  257. bool Storage::healthy(void)
  258. {
  259. return _initialised && AP_HAL::millis() - _last_empty_ms < 2000;
  260. }