nxffs_initialize.c 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582
  1. /****************************************************************************
  2. * fs/nxffs/nxffs_initialize.c
  3. *
  4. * Copyright (C) 2011, 2013, 2015, 2017-2018 Gregory Nutt. All rights
  5. * reserved.
  6. * Author: Gregory Nutt <gnutt@nuttx.org>
  7. *
  8. * References: Linux/Documentation/filesystems/romfs.txt
  9. *
  10. * Redistribution and use in source and binary forms, with or without
  11. * modification, are permitted provided that the following conditions
  12. * are met:
  13. *
  14. * 1. Redistributions of source code must retain the above copyright
  15. * notice, this list of conditions and the following disclaimer.
  16. * 2. Redistributions in binary form must reproduce the above copyright
  17. * notice, this list of conditions and the following disclaimer in
  18. * the documentation and/or other materials provided with the
  19. * distribution.
  20. * 3. Neither the name NuttX nor the names of its contributors may be
  21. * used to endorse or promote products derived from this software
  22. * without specific prior written permission.
  23. *
  24. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  25. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  26. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  27. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  28. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  29. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  30. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
  31. * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
  32. * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  33. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  34. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  35. * POSSIBILITY OF SUCH DAMAGE.
  36. *
  37. ****************************************************************************/
  38. /****************************************************************************
  39. * Included Files
  40. ****************************************************************************/
  41. #include <nuttx/config.h>
  42. #include <string.h>
  43. #include <errno.h>
  44. #include <assert.h>
  45. #include <debug.h>
  46. #include <nuttx/kmalloc.h>
  47. #include <nuttx/mtd/mtd.h>
  48. #include <nuttx/fs/fs.h>
  49. #include <nuttx/fs/ioctl.h>
  50. #include "nxffs.h"
  51. /****************************************************************************
  52. * Private Data
  53. ****************************************************************************/
  54. /* See fs_mount.c -- this structure is explicitly externed there.
  55. * We use the old-fashioned kind of initializers so that this will compile
  56. * with any compiler.
  57. */
  58. const struct mountpt_operations nxffs_operations =
  59. {
  60. nxffs_open, /* open */
  61. nxffs_close, /* close */
  62. nxffs_read, /* read */
  63. nxffs_write, /* write */
  64. NULL, /* seek -- Use f_pos in struct file */
  65. nxffs_ioctl, /* ioctl */
  66. NULL, /* sync -- No buffered data */
  67. nxffs_dup, /* dup */
  68. nxffs_fstat, /* fstat */
  69. #ifdef __NO_TRUNCATE_SUPPORT__
  70. nxffs_truncate, /* truncate */
  71. #else
  72. NULL, /* truncate */
  73. #endif
  74. nxffs_opendir, /* opendir */
  75. NULL, /* closedir */
  76. nxffs_readdir, /* readdir */
  77. nxffs_rewinddir, /* rewinddir */
  78. nxffs_bind, /* bind */
  79. nxffs_unbind, /* unbind */
  80. nxffs_statfs, /* statfs */
  81. nxffs_unlink, /* unlink */
  82. NULL, /* mkdir -- no directories */
  83. NULL, /* rmdir -- no directories */
  84. NULL, /* rename -- cannot rename in place if name is longer */
  85. nxffs_stat /* stat */
  86. };
  87. /****************************************************************************
  88. * Public Data
  89. ****************************************************************************/
  90. /* The magic number that appears that the beginning of each NXFFS (logical)
  91. * block
  92. */
  93. const uint8_t g_blockmagic[NXFFS_MAGICSIZE] =
  94. {
  95. 'B', 'l', 'c', 'k'
  96. };
  97. /* The magic number that appears that the beginning of each NXFFS inode */
  98. const uint8_t g_inodemagic[NXFFS_MAGICSIZE] =
  99. {
  100. 'I', 'n', 'o', 'd'
  101. };
  102. /* The magic number that appears that the beginning of each NXFFS inode
  103. * data block.
  104. */
  105. const uint8_t g_datamagic[NXFFS_MAGICSIZE] =
  106. {
  107. 'D', 'a', 't', 'a'
  108. };
  109. /* If CONFIG_NXFFS_PREALLOCATED is defined, then this is the single, pre-
  110. * allocated NXFFS volume instance.
  111. */
  112. #ifdef CONFIG_NXFFS_PREALLOCATED
  113. struct nxffs_volume_s g_volume;
  114. #endif
  115. /****************************************************************************
  116. * Public Functions
  117. ****************************************************************************/
  118. /****************************************************************************
  119. * Name: nxffs_initialize
  120. *
  121. * Description:
  122. * Initialize to provide NXFFS on an MTD interface
  123. *
  124. * Input Parameters:
  125. * mtd - The MTD device that supports the FLASH interface.
  126. *
  127. * Returned Value:
  128. * Zero is returned on success. Otherwise, a negated errno value is
  129. * returned to indicate the nature of the failure.
  130. *
  131. ****************************************************************************/
  132. int nxffs_initialize(FAR struct mtd_dev_s *mtd)
  133. {
  134. FAR struct nxffs_volume_s *volume;
  135. #ifdef CONFIG_NXFFS_SCAN_VOLUME
  136. struct nxffs_blkstats_s stats;
  137. off_t threshold;
  138. #endif
  139. int ret;
  140. /* If CONFIG_NXFFS_PREALLOCATED is defined, then this is the single, pre-
  141. * allocated NXFFS volume instance.
  142. */
  143. #ifdef CONFIG_NXFFS_PREALLOCATED
  144. volume = &g_volume;
  145. memset(volume, 0, sizeof(struct nxffs_volume_s));
  146. #else
  147. /* Allocate a NXFFS volume structure */
  148. volume = kmm_zalloc(sizeof(struct nxffs_volume_s));
  149. if (!volume)
  150. {
  151. return -ENOMEM;
  152. }
  153. #endif
  154. /* Initialize the NXFFS volume structure */
  155. volume->mtd = mtd;
  156. volume->cblock = (off_t)-1;
  157. nxsem_init(&volume->exclsem, 0, 1);
  158. nxsem_init(&volume->wrsem, 0, 1);
  159. /* Get the volume geometry. (casting to uintptr_t first eliminates
  160. * complaints on some architectures where the sizeof long is different
  161. * from the size of a pointer).
  162. */
  163. ret = MTD_IOCTL(mtd, MTDIOC_GEOMETRY,
  164. (unsigned long)((uintptr_t)&volume->geo));
  165. if (ret < 0)
  166. {
  167. ferr("ERROR: MTD ioctl(MTDIOC_GEOMETRY) failed: %d\n", -ret);
  168. goto errout_with_volume;
  169. }
  170. /* Allocate one I/O block buffer to general files system access */
  171. volume->cache = (FAR uint8_t *)kmm_malloc(volume->geo.blocksize);
  172. if (!volume->cache)
  173. {
  174. ferr("ERROR: Failed to allocate an erase block buffer\n");
  175. ret = -ENOMEM;
  176. goto errout_with_volume;
  177. }
  178. /* Pre-allocate one, full, in-memory erase block. This is needed for
  179. * filesystem packing (but is useful in other places as well). This buffer
  180. * is not needed often, but is best to have pre-allocated and in-place.
  181. */
  182. volume->pack = (FAR uint8_t *)kmm_malloc(volume->geo.erasesize);
  183. if (!volume->pack)
  184. {
  185. ferr("ERROR: Failed to allocate an I/O block buffer\n");
  186. ret = -ENOMEM;
  187. goto errout_with_cache;
  188. }
  189. /* Get the number of R/W blocks per erase block and the total number o
  190. * R/W blocks
  191. */
  192. volume->blkper = volume->geo.erasesize / volume->geo.blocksize;
  193. volume->nblocks = volume->geo.neraseblocks * volume->blkper;
  194. DEBUGASSERT((off_t)volume->blkper * volume->geo.blocksize ==
  195. volume->geo.erasesize);
  196. #ifdef CONFIG_NXFFS_SCAN_VOLUME
  197. /* Check if there is a valid NXFFS file system on the flash */
  198. ret = nxffs_blockstats(volume, &stats);
  199. if (ret < 0)
  200. {
  201. ferr("ERROR: Failed to collect block statistics: %d\n", -ret);
  202. goto errout_with_buffer;
  203. }
  204. /* If the proportion of good blocks is low or the proportion of unformatted
  205. * blocks is high, then reformat the FLASH.
  206. */
  207. threshold = (stats.nblocks * CONFIG_NXFFS_REFORMAT_THRESH) / 100;
  208. if (stats.ngood < threshold || stats.nunformat > threshold)
  209. {
  210. /* Reformat the volume */
  211. ret = nxffs_reformat(volume);
  212. if (ret < 0)
  213. {
  214. ferr("ERROR: Failed to reformat the volume: %d\n", -ret);
  215. goto errout_with_buffer;
  216. }
  217. /* Get statistics on the re-formatted volume */
  218. #if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_DEBUG_FS)
  219. ret = nxffs_blockstats(volume, &stats);
  220. if (ret < 0)
  221. {
  222. ferr("ERROR: Failed to collect block statistics: %d\n", -ret);
  223. goto errout_with_buffer;
  224. }
  225. #endif
  226. }
  227. #endif /* CONFIG_NXFFS_SCAN_VOLUME */
  228. /* Get the file system limits */
  229. ret = nxffs_limits(volume);
  230. if (ret == OK)
  231. {
  232. return OK;
  233. }
  234. /* We may need to format the volume. Try that before giving up. */
  235. fwarn("WARNING: Failed to calculate file system limits: %d\n", -ret);
  236. ret = nxffs_reformat(volume);
  237. if (ret < 0)
  238. {
  239. ferr("ERROR: Failed to reformat the volume: %d\n", -ret);
  240. goto errout_with_buffer;
  241. }
  242. /* Get statistics on the re-formatted volume */
  243. #if defined(CONFIG_NXFFS_SCAN_VOLUME) && defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_DEBUG_FS)
  244. ret = nxffs_blockstats(volume, &stats);
  245. if (ret < 0)
  246. {
  247. ferr("ERROR: Failed to collect block statistics: %d\n", -ret);
  248. goto errout_with_buffer;
  249. }
  250. #endif
  251. /* Now try to get the file system limits again */
  252. ret = nxffs_limits(volume);
  253. if (ret == OK)
  254. {
  255. return OK;
  256. }
  257. /* Now give up */
  258. ferr("ERROR: Failed to calculate file system limits: %d\n", -ret);
  259. errout_with_buffer:
  260. kmm_free(volume->pack);
  261. errout_with_cache:
  262. kmm_free(volume->cache);
  263. errout_with_volume:
  264. #ifndef CONFIG_NXFFS_PREALLOCATED
  265. kmm_free(volume);
  266. #endif
  267. return ret;
  268. }
  269. /****************************************************************************
  270. * Name: nxffs_limits
  271. *
  272. * Description:
  273. * Recalculate file system limits: (1) the FLASH offset to the first,
  274. * valid inode, and (2) the FLASH offset to the first, unused byte after
  275. * the last inode (invalid or not).
  276. *
  277. * The first, lower limit must be recalculated: (1) initially, (2)
  278. * whenever the first inode is deleted, or (3) whenever inode is moved
  279. * as part of the file system packing operation.
  280. *
  281. * The second, upper limit must be (1) incremented whenever new file
  282. * data is written, or (2) recalculated as part of the file system packing
  283. * operation.
  284. *
  285. * Input Parameters:
  286. * volume - Identifies the NXFFS volume
  287. *
  288. * Returned Value:
  289. * Zero on success. Otherwise, a negated error is returned indicating the
  290. * nature of the failure.
  291. *
  292. ****************************************************************************/
  293. int nxffs_limits(FAR struct nxffs_volume_s *volume)
  294. {
  295. FAR struct nxffs_entry_s entry;
  296. off_t block;
  297. off_t offset;
  298. bool noinodes = false;
  299. int nerased;
  300. int ret;
  301. /* Get the offset to the first valid block on the FLASH */
  302. block = 0;
  303. ret = nxffs_validblock(volume, &block);
  304. if (ret < 0)
  305. {
  306. ferr("ERROR: Failed to find a valid block: %d\n", -ret);
  307. return ret;
  308. }
  309. /* Then find the first valid inode in or beyond the first valid block */
  310. offset = block * volume->geo.blocksize;
  311. ret = nxffs_nextentry(volume, offset, &entry);
  312. if (ret < 0)
  313. {
  314. /* The value -ENOENT is special. This simply means that the FLASH
  315. * was searched to the end and no valid inode was found... the file
  316. * system is empty (or, in more perverse cases, all inodes are
  317. * deleted or corrupted).
  318. */
  319. if (ret != -ENOENT)
  320. {
  321. ferr("ERROR: nxffs_nextentry failed: %d\n", -ret);
  322. return ret;
  323. }
  324. /* Set a flag the just indicates that no inodes were found. Later,
  325. * we will set the location of the first inode to be the same as
  326. * the location of the free FLASH region.
  327. */
  328. finfo("No inodes found\n");
  329. noinodes = true;
  330. }
  331. else
  332. {
  333. /* Save the offset to the first inode */
  334. volume->inoffset = entry.hoffset;
  335. finfo("First inode at offset %d\n", volume->inoffset);
  336. /* Discard this entry and set the next offset. */
  337. offset = nxffs_inodeend(volume, &entry);
  338. nxffs_freeentry(&entry);
  339. }
  340. /* Now, search for the last valid entry */
  341. if (!noinodes)
  342. {
  343. while (nxffs_nextentry(volume, offset, &entry) == OK)
  344. {
  345. /* Discard the entry and guess the next offset. */
  346. offset = nxffs_inodeend(volume, &entry);
  347. nxffs_freeentry(&entry);
  348. }
  349. finfo("Last inode before offset %d\n", offset);
  350. }
  351. /* No inodes were found after this offset. Now search for a block of
  352. * erased flash.
  353. */
  354. nxffs_ioseek(volume, offset);
  355. nerased = 0;
  356. for (; ; )
  357. {
  358. int ch = nxffs_getc(volume, 1);
  359. if (ch < 0)
  360. {
  361. /* Failed to read the next byte... this could mean that the FLASH
  362. * is full?
  363. */
  364. if (volume->ioblock + 1 >= volume->nblocks &&
  365. volume->iooffset + 1 >= volume->geo.blocksize)
  366. {
  367. /* Yes.. the FLASH is full. Force the offsets to the end of
  368. * FLASH
  369. */
  370. volume->froffset = volume->nblocks * volume->geo.blocksize;
  371. finfo("Assume no free FLASH, froffset: %d\n",
  372. volume->froffset);
  373. if (noinodes)
  374. {
  375. volume->inoffset = volume->froffset;
  376. finfo("No inodes, inoffset: %d\n", volume->inoffset);
  377. }
  378. return OK;
  379. }
  380. /* No? Then it is some other failure that we do not know how to
  381. * handle
  382. */
  383. ferr("ERROR: nxffs_getc failed: %d\n", -ch);
  384. return ch;
  385. }
  386. /* Check for another erased byte */
  387. else if (ch == CONFIG_NXFFS_ERASEDSTATE)
  388. {
  389. /* If we have encountered NXFFS_NERASED number of consecutive
  390. * erased bytes, then presume we have reached the end of valid
  391. * data.
  392. */
  393. if (++nerased >= NXFFS_NERASED)
  394. {
  395. /* Okay.. we have a long stretch of erased FLASH in a valid
  396. * FLASH block. Let's say that this is the beginning of
  397. * the free FLASH region.
  398. */
  399. volume->froffset = offset;
  400. finfo("Free FLASH region begins at offset: %d\n",
  401. volume->froffset);
  402. if (noinodes)
  403. {
  404. volume->inoffset = offset;
  405. finfo("First inode at offset %d\n", volume->inoffset);
  406. }
  407. return OK;
  408. }
  409. }
  410. else
  411. {
  412. volume->ioblock += 1;
  413. volume->iooffset = SIZEOF_NXFFS_BLOCK_HDR;
  414. offset = volume->ioblock * volume->geo.blocksize +
  415. volume->iooffset;
  416. nerased = 0;
  417. }
  418. }
  419. /* Won't get here */
  420. return OK;
  421. }
  422. /****************************************************************************
  423. * Name: nxffs_bind
  424. *
  425. * Description:
  426. * This function implements a portion of the mount operation. Normmally,
  427. * the bind() method allocates and initializes the mountpoint private data
  428. * then binds the blockdriver inode to the filesystem private data. The
  429. * final binding of the private data (containing the blockdriver) to the
  430. * mountpoint is performed by mount().
  431. *
  432. * For the NXFFS, this sequence is quite different for the following
  433. * reasons:
  434. *
  435. * 1. A block driver is not used. Instead, an MTD instance was provided
  436. * to nxfs_initialize prior to mounting. So, in this sense, the NXFFS
  437. * file system is already bound.
  438. *
  439. * 2. Since the volume was already bound to the MTD driver, all allocations
  440. * and initializations have already been performed. Essentially, all
  441. * mount operations have been bypassed and now we just need to provide
  442. * the pre-allocated volume instance.
  443. *
  444. * 3. The tricky thing is that there is no mechanism to associate multiple
  445. * NXFFS volumes to the multiple volumes bound to different MTD drivers.
  446. * Hence, the limitation of a single NXFFS volume.
  447. *
  448. ****************************************************************************/
  449. int nxffs_bind(FAR struct inode *blkdriver, FAR const void *data,
  450. FAR void **handle)
  451. {
  452. #ifndef CONFIG_NXFFS_PREALLOCATED
  453. # error "No design to support dynamic allocation of volumes"
  454. #else
  455. /* If CONFIG_NXFFS_PREALLOCATED is defined, then this is the single, pre-
  456. * allocated NXFFS volume instance.
  457. */
  458. DEBUGASSERT(g_volume.cache);
  459. *handle = &g_volume;
  460. #endif
  461. return OK;
  462. }
  463. /****************************************************************************
  464. * Name: nxffs_unbind
  465. *
  466. * Description: This implements the filesystem portion of the umount
  467. * operation.
  468. *
  469. ****************************************************************************/
  470. int nxffs_unbind(FAR void *handle, FAR struct inode **blkdriver,
  471. unsigned int flags)
  472. {
  473. #ifndef CONFIG_NXFFS_PREALLOCATED
  474. # error "No design to support dynamic allocation of volumes"
  475. #else
  476. /* This implementation currently only supports unmounting if there are no
  477. * open file references.
  478. */
  479. if (flags != 0)
  480. {
  481. return -ENOSYS;
  482. }
  483. return g_volume.ofiles ? -EBUSY : OK;
  484. #endif
  485. }