nxffs.h 41 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142
  1. /****************************************************************************
  2. * fs/nxffs/nxffs.h
  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. #ifndef __FS_NXFFS_NXFFS_H
  39. #define __FS_NXFFS_NXFFS_H
  40. /****************************************************************************
  41. * Included Files
  42. ****************************************************************************/
  43. #include <nuttx/config.h>
  44. #include <sys/types.h>
  45. #include <stdint.h>
  46. #include <stdbool.h>
  47. #include <nuttx/mtd/mtd.h>
  48. #include <nuttx/fs/nxffs.h>
  49. #include <nuttx/semaphore.h>
  50. /****************************************************************************
  51. * Pre-processor Definitions
  52. ****************************************************************************/
  53. /* NXFFS Definitions ********************************************************/
  54. /* General NXFFS organization. The following example assumes 4 logical
  55. * blocks per FLASH erase block. The actual relationship is determined by
  56. * the FLASH geometry reported by the MTD driver.
  57. *
  58. * ERASE LOGICAL Inodes begin with a inode header which may
  59. * BLOCK BLOCK CONTENTS be marked as deleted, pending re-packing.
  60. * n 4*n --+--------------+
  61. * |BBBBBBBBBBBBBB| Logic block header
  62. * |IIIIIIIIIIIIII| Inodes begin with a inode header
  63. * |DDDDDDDDDDDDDD| Data block containing inode data block
  64. * | (Inode Data) |
  65. * 4*n+1 --+--------------+
  66. * |BBBBBBBBBBBBBB| Logic block header
  67. * |DDDDDDDDDDDDDD| Inodes may consist multiple data blocks
  68. * | (Inode Data) |
  69. * |IIIIIIIIIIIIII| Next inode header
  70. * | | Possibly unused bytes at the end of block
  71. * 4*n+2 --+--------------+
  72. * |BBBBBBBBBBBBBB| Logic block header
  73. * |DDDDDDDDDDDDDD|
  74. * | (Inode Data) |
  75. * 4*n+3 --+--------------+
  76. * |BBBBBBBBBBBBBB| Logic block header
  77. * |IIIIIIIIIIIIII| Next inode header
  78. * |DDDDDDDDDDDDDD|
  79. * | (Inode Data) |
  80. * n+1 4*(n+1) --+--------------+
  81. * |BBBBBBBBBBBBBB| Logic block header
  82. * | | All FLASH is unused after the end of the
  83. * | | final inode.
  84. * --+--------------+
  85. *
  86. * General operation:
  87. * Inodes are written starting at the beginning of FLASH. As inodes are
  88. * deleted, they are marked as deleted but not removed. As new inodes are
  89. * written, allocations proceed to toward the end of the FLASH -- thus,
  90. * supporting wear leveling by using all FLASH blocks equally.
  91. *
  92. * When the FLASH becomes full (no more space at the end of the FLASH), a
  93. * re-packing operation must be performed: All inodes marked deleted are
  94. * finally removed and the remaining inodes are packed at the beginning of
  95. * the FLASH. Allocations then continue at the freed FLASH memory at the
  96. * end of the FLASH.
  97. *
  98. * BLOCK HEADER:
  99. * The block header is used to determine if the block has every been
  100. * formatted and also indicates bad blocks which should never be used.
  101. *
  102. * INODE HEADER:
  103. * Each inode begins with an inode header that contains, among other
  104. * things, the name of the inode, the offset to the first data block,
  105. * and the length of the inode data.
  106. *
  107. * At present, the only kind of inode support is a file. So for now, the
  108. * term file and inode are interchangeable.
  109. *
  110. * INODE DATA HEADER:
  111. * Inode data is enclosed in a data header. For a given inode, there
  112. * is at most one inode data block per logical block. If the inode data
  113. * spans more than one logical block, then the inode data may be enclosed
  114. * in multiple data blocks, one per logical block.
  115. *
  116. * NXFFS Limitations:
  117. * 1. Since the files are contiguous in FLASH and since allocations always
  118. * proceed toward the end of the FLASH, there can only be one file opened
  119. * for writing at a time. Multiple files may be opened for reading.
  120. * 2. Files may not be increased in size after they have been closed. The
  121. * O_APPEND open flag is not supported.
  122. * 3. Files are always written sequential. Seeking within a file opened for
  123. * writing will not work.
  124. * 4. There are no directories, however, '/' may be used within a file name
  125. * string providing some illusion of directories.
  126. * 5. Files may be opened for reading or for writing, but not both: The
  127. * O_RDWR open flag is not supported.
  128. * 6. The re-packing process occurs only during a write when the free FLASH
  129. * memory at the end of the FLASH is exhausted. Thus, occasionally, file
  130. * writing may take a long time.
  131. * 7. Another limitation is that there can be only a single NXFFS volume
  132. * mounted at any time. This has to do with the fact that we bind to
  133. * an MTD driver (instead of a block driver) and bypass all of the normal
  134. * mount operations.
  135. */
  136. /* Values for logical block state. Basically, there are only two, perhaps
  137. * three, states:
  138. *
  139. * BLOCK_STATE_GOOD - The block is not known to be bad.
  140. * BLOCK_STATE_BAD - An error was found on the block and it is marked bad.
  141. * Other values - The block is bad and has an invalid state.
  142. *
  143. * Care is taken so that the GOOD to BAD transition only involves burning
  144. * bits from the erased to non-erased state.
  145. */
  146. #define BLOCK_STATE_GOOD (CONFIG_NXFFS_ERASEDSTATE ^ 0x44)
  147. #define BLOCK_STATE_BAD (CONFIG_NXFFS_ERASEDSTATE ^ 0x55)
  148. /* Values for NXFFS inode state. Similar there are 2 (maybe 3) inode states:
  149. *
  150. * INODE_STATE_FILE - The inode is a valid usable, file
  151. * INODE_STATE_DELETED - The inode has been deleted.
  152. * Other values - The inode is bad and has an invalid state.
  153. *
  154. * Care is taken so that the VALID to DELETED transition only involves
  155. * burning bits from the erased to non-erased state.
  156. */
  157. #define INODE_STATE_FILE (CONFIG_NXFFS_ERASEDSTATE ^ 0x22)
  158. #define INODE_STATE_DELETED (CONFIG_NXFFS_ERASEDSTATE ^ 0xaa)
  159. /* Number of bytes in an the NXFFS magic sequences */
  160. #define NXFFS_MAGICSIZE 4
  161. /* When we allocate FLASH for a new inode data block, we will require that
  162. * space is available to hold this minimum number of data bytes in addition
  163. * to the size of the data block headeer.
  164. */
  165. #define NXFFS_MINDATA 16
  166. /* Internal definitions *****************************************************/
  167. /* If we encounter this number of erased bytes, we assume that all of the
  168. * flash beyond this point is erased.
  169. */
  170. #define NXFFS_NERASED 128
  171. /* Quasi-standard definitions */
  172. #ifndef MIN
  173. # define MIN(a,b) (a < b ? a : b)
  174. #endif
  175. #ifndef MAX
  176. # define MAX(a,b) (a > b ? a : b)
  177. #endif
  178. /****************************************************************************
  179. * Public Types
  180. ****************************************************************************/
  181. /* This structure defines each packed block on the FLASH media */
  182. struct nxffs_block_s
  183. {
  184. uint8_t magic[4]; /* 0-3: Magic number for valid block */
  185. uint8_t state; /* 4: Block state: See BLOCK_STATE_* */
  186. };
  187. #define SIZEOF_NXFFS_BLOCK_HDR 5
  188. /* This structure defines each packed NXFFS inode header on the FLASH media */
  189. struct nxffs_inode_s
  190. {
  191. uint8_t magic[4]; /* 0-3: Magic number for valid inode */
  192. uint8_t state; /* 4: Inode state: See INODE_STATE_* */
  193. uint8_t namlen; /* 5: Length of the inode name */
  194. uint8_t noffs[4]; /* 6-9: FLASH offset to the file name */
  195. uint8_t doffs[4]; /* 10-13: FLASH offset to the first data block */
  196. uint8_t utc[4]; /* 14-17: Creation time */
  197. uint8_t crc[4]; /* 18-21: CRC32 */
  198. uint8_t datlen[4]; /* 22-25: Length of data in bytes */
  199. };
  200. #define SIZEOF_NXFFS_INODE_HDR 26
  201. /* This structure defines each packed NXFFS data header on the FLASH media */
  202. struct nxffs_data_s
  203. {
  204. uint8_t magic[4]; /* 0-3: Magic number for valid data */
  205. uint8_t crc[4]; /* 4-7: CRC32 */
  206. uint8_t datlen[2]; /* 8-9: Length of data in bytes */
  207. };
  208. #define SIZEOF_NXFFS_DATA_HDR 10
  209. /* This is an in-memory representation of the NXFFS inode as extracted from
  210. * FLASH and with additional state information.
  211. */
  212. struct nxffs_entry_s
  213. {
  214. off_t hoffset; /* FLASH offset to the inode header */
  215. off_t noffset; /* FLASH offset to the inode name */
  216. off_t doffset; /* FLASH offset to the first data header */
  217. FAR char *name; /* inode name */
  218. uint32_t utc; /* Time stamp */
  219. uint32_t datlen; /* Length of inode data */
  220. };
  221. /* This structure describes int in-memory representation of the data block */
  222. struct nxffs_blkentry_s
  223. {
  224. off_t hoffset; /* Offset to the block data header */
  225. uint16_t datlen; /* Length of data following the header */
  226. uint16_t foffset; /* Offset to start of data */
  227. };
  228. /* This structure describes the state of one open file. This structure
  229. * is protected by the volume semaphore.
  230. */
  231. struct nxffs_ofile_s
  232. {
  233. struct nxffs_ofile_s *flink; /* Supports a singly linked list */
  234. int16_t crefs; /* Reference count */
  235. mode_t oflags; /* Open mode */
  236. struct nxffs_entry_s entry; /* Describes the NXFFS inode entry */
  237. };
  238. /* A file opened for writing require some additional information */
  239. struct nxffs_wrfile_s
  240. {
  241. /* The following fields provide the common open file information. */
  242. struct nxffs_ofile_s ofile;
  243. /* The following fields are required to support the write operation */
  244. bool truncate; /* Delete a file of the same name */
  245. uint16_t datlen; /* Number of bytes written in data block */
  246. off_t doffset; /* FLASH offset to the current data header */
  247. uint32_t crc; /* Accumulated data block CRC */
  248. };
  249. /* This structure represents the overall state of on NXFFS instance. */
  250. struct nxffs_volume_s
  251. {
  252. FAR struct mtd_dev_s *mtd; /* Supports FLASH access */
  253. sem_t exclsem; /* Used to assure thread-safe access */
  254. sem_t wrsem; /* Enforces single writer restriction */
  255. struct mtd_geometry_s geo; /* Device geometry */
  256. uint8_t blkper; /* R/W blocks per erase block */
  257. uint16_t iooffset; /* Next offset in read/write access (in ioblock) */
  258. off_t inoffset; /* Offset to the first valid inode header */
  259. off_t froffset; /* Offset to the first free byte */
  260. off_t nblocks; /* Number of R/W blocks on volume */
  261. off_t ioblock; /* Current block number being accessed */
  262. off_t cblock; /* Starting block number in cache */
  263. FAR struct nxffs_ofile_s *ofiles; /* A singly-linked list of open files */
  264. FAR uint8_t *cache; /* On cached erase block for general I/O */
  265. FAR uint8_t *pack; /* A full erase block to support packing */
  266. };
  267. /* This structure describes the state of the blocks on the NXFFS volume */
  268. struct nxffs_blkstats_s
  269. {
  270. off_t nblocks; /* Total number of FLASH blocks */
  271. off_t ngood; /* Number of good FLASH blocks found */
  272. off_t nbad; /* Number of well-formatted FLASH blocks marked as bad */
  273. off_t nunformat; /* Number of unformatted FLASH blocks */
  274. off_t ncorrupt; /* Number of blocks with corrupted format info */
  275. off_t nbadread; /* Number of blocks that could not be read */
  276. };
  277. /****************************************************************************
  278. * Public Data
  279. ****************************************************************************/
  280. /* The magic number that appears that the beginning of each NXFFS (logical)
  281. * block
  282. */
  283. extern const uint8_t g_blockmagic[NXFFS_MAGICSIZE];
  284. /* The magic number that appears that the beginning of each NXFFS inode */
  285. extern const uint8_t g_inodemagic[NXFFS_MAGICSIZE];
  286. /* The magic number that appears that the beginning of each NXFFS inode
  287. * data block.
  288. */
  289. extern const uint8_t g_datamagic[NXFFS_MAGICSIZE];
  290. /* If CONFIG_NXFFS_PREALLOCATED is defined, then this is the single, pre-
  291. * allocated NXFFS volume instance.
  292. */
  293. #ifdef CONFIG_NXFFS_PREALLOCATED
  294. extern struct nxffs_volume_s g_volume;
  295. #endif
  296. /****************************************************************************
  297. * Public Function Prototypes
  298. ****************************************************************************/
  299. /****************************************************************************
  300. * Name: nxffs_limits
  301. *
  302. * Description:
  303. * Recalculate file system limits: (1) the FLASH offset to the first,
  304. * valid inode, and (2) the FLASH offset to the first, unused byte after
  305. * the last inode (invalid or not).
  306. *
  307. * The first, lower limit must be recalculated: (1) initially, (2)
  308. * whenever the first inode is deleted, or (3) whenever inode is moved
  309. * as part of the file system packing operation.
  310. *
  311. * The second, upper limit must be (1) incremented whenever new file
  312. * data is written, or (2) recalculated as part of the file system packing
  313. * operation.
  314. *
  315. * Input Parameters:
  316. * volume - Identifies the NXFFS volume
  317. *
  318. * Returned Value:
  319. * Zero on success. Otherwise, a negated error is returned indicating the
  320. * nature of the failure.
  321. *
  322. * Defined in nxffs_initialize.c
  323. *
  324. ****************************************************************************/
  325. int nxffs_limits(FAR struct nxffs_volume_s *volume);
  326. /****************************************************************************
  327. * Name: nxffs_rdle16
  328. *
  329. * Description:
  330. * Get a (possibly unaligned) 16-bit little endian value.
  331. *
  332. * Input Parameters:
  333. * val - A pointer to the first byte of the little endian value.
  334. *
  335. * Returned Value:
  336. * A uint16_t representing the whole 16-bit integer value
  337. *
  338. * Defined in nxffs_util.c
  339. *
  340. ****************************************************************************/
  341. uint16_t nxffs_rdle16(FAR const uint8_t *val);
  342. /****************************************************************************
  343. * Name: nxffs_wrle16
  344. *
  345. * Description:
  346. * Put a (possibly unaligned) 16-bit little endian value.
  347. *
  348. * Input Parameters:
  349. * dest - A pointer to the first byte to save the little endian value.
  350. * val - The 16-bit value to be saved.
  351. *
  352. * Returned Value:
  353. * None
  354. *
  355. * Defined in nxffs_util.c
  356. *
  357. ****************************************************************************/
  358. void nxffs_wrle16(uint8_t *dest, uint16_t val);
  359. /****************************************************************************
  360. * Name: nxffs_rdle32
  361. *
  362. * Description:
  363. * Get a (possibly unaligned) 32-bit little endian value.
  364. *
  365. * Input Parameters:
  366. * val - A pointer to the first byte of the little endian value.
  367. *
  368. * Returned Value:
  369. * A uint32_t representing the whole 32-bit integer value
  370. *
  371. * Defined in nxffs_util.c
  372. *
  373. ****************************************************************************/
  374. uint32_t nxffs_rdle32(FAR const uint8_t *val);
  375. /****************************************************************************
  376. * Name: nxffs_wrle32
  377. *
  378. * Description:
  379. * Put a (possibly unaligned) 32-bit little endian value.
  380. *
  381. * Input Parameters:
  382. * dest - A pointer to the first byte to save the little endian value.
  383. * val - The 32-bit value to be saved.
  384. *
  385. * Returned Value:
  386. * None
  387. *
  388. * Defined in nxffs_util.c
  389. *
  390. ****************************************************************************/
  391. void nxffs_wrle32(uint8_t *dest, uint32_t val);
  392. /****************************************************************************
  393. * Name: nxffs_erased
  394. *
  395. * Description:
  396. * Check if a block of memory is in the erased state.
  397. *
  398. * Input Parameters:
  399. * buffer - Address of the start of the memory to check.
  400. * buflen - The number of bytes to check.
  401. *
  402. * Returned Value:
  403. * The number of erased bytes found at the beginning of the memory region.
  404. *
  405. * Defined in nxffs_util.c
  406. *
  407. ****************************************************************************/
  408. size_t nxffs_erased(FAR const uint8_t *buffer, size_t buflen);
  409. /****************************************************************************
  410. * Name: nxffs_rdcache
  411. *
  412. * Description:
  413. * Read one I/O block into the volume cache memory.
  414. *
  415. * Input Parameters:
  416. * volume - Describes the current volume
  417. * block - The first logical block to read
  418. *
  419. * Returned Value:
  420. * Negated errnos are returned only in the case of MTD reported failures.
  421. * Nothing in the volume data itself will generate errors.
  422. *
  423. * Defined in nxffs_cache.c
  424. *
  425. ****************************************************************************/
  426. int nxffs_rdcache(FAR struct nxffs_volume_s *volume, off_t block);
  427. /****************************************************************************
  428. * Name: nxffs_wrcache
  429. *
  430. * Description:
  431. * Write one or more logical blocks from the volume cache memory.
  432. *
  433. * Input Parameters:
  434. * volume - Describes the current volume
  435. *
  436. * Returned Value:
  437. * Negated errnos are returned only in the case of MTD reported failures.
  438. *
  439. * Defined in nxffs_cache.c
  440. *
  441. ****************************************************************************/
  442. int nxffs_wrcache(FAR struct nxffs_volume_s *volume);
  443. /****************************************************************************
  444. * Name: nxffs_ioseek
  445. *
  446. * Description:
  447. * Seek to a position in FLASH memory. This simply sets up the offsets
  448. * and pointer values. This is a necessary step prior to using
  449. * nxffs_getc().
  450. *
  451. * Input Parameters:
  452. * volume - Describes the NXFFS volume
  453. * offset - The physical offset in bytes from the beginning of the FLASH
  454. * in bytes.
  455. *
  456. * Defined in nxffs_cache.c
  457. *
  458. ****************************************************************************/
  459. void nxffs_ioseek(FAR struct nxffs_volume_s *volume, off_t offset);
  460. /****************************************************************************
  461. * Name: nxffs_iotell
  462. *
  463. * Description:
  464. * Report the current position.
  465. *
  466. * Input Parameters:
  467. * volume - Describes the NXFFS volume
  468. *
  469. * Returned Value:
  470. * The offset from the beginning of FLASH to the current seek position.
  471. *
  472. * Defined in nxffs_cache.c
  473. *
  474. ****************************************************************************/
  475. off_t nxffs_iotell(FAR struct nxffs_volume_s *volume);
  476. /****************************************************************************
  477. * Name: nxffs_getc
  478. *
  479. * Description:
  480. * Get the next byte from FLASH. This function allows the data in the
  481. * formatted FLASH blocks to be read as a continuous byte stream, skipping
  482. * over bad blocks and block headers as necessary.
  483. *
  484. * Input Parameters:
  485. * volume - Describes the NXFFS volume. The parameters ioblock and iooffset
  486. * in the volume structure determine the behavior of nxffs_getc().
  487. * reserve - If less than this much space is available at the end of the
  488. * block, then skip to the next block.
  489. *
  490. * Returned Value:
  491. * Zero is returned on success. Otherwise, a negated errno indicating the
  492. * nature of the failure.
  493. *
  494. * Defined in nxffs_cache.c
  495. *
  496. ****************************************************************************/
  497. int nxffs_getc(FAR struct nxffs_volume_s *volume, uint16_t reserve);
  498. /****************************************************************************
  499. * Name: nxffs_freeentry
  500. *
  501. * Description:
  502. * The inode values returned by nxffs_nextentry() include allocated memory
  503. * (specifically, the file name string). This function should be called
  504. * to dispose of that memory when the inode entry is no longer needed.
  505. *
  506. * Note that the nxffs_entry_s containing structure is not freed. The
  507. * caller may call kmm_free upon return of this function if necessary to
  508. * free the entry container.
  509. *
  510. * Input Parameters:
  511. * entry - The entry to be freed.
  512. *
  513. * Returned Value:
  514. * None
  515. *
  516. * Defined in nxffs_inode.c
  517. *
  518. ****************************************************************************/
  519. void nxffs_freeentry(FAR struct nxffs_entry_s *entry);
  520. /****************************************************************************
  521. * Name: nxffs_nextentry
  522. *
  523. * Description:
  524. * Search for the next valid inode starting at the provided FLASH offset.
  525. *
  526. * Input Parameters:
  527. * volume - Describes the NXFFS volume.
  528. * offset - The FLASH memory offset to begin searching.
  529. * entry - A pointer to memory provided by the caller in which to return
  530. * the inode description.
  531. *
  532. * Returned Value:
  533. * Zero is returned on success. Otherwise, a negated errno is returned
  534. * that indicates the nature of the failure.
  535. *
  536. * Defined in nxffs_inode.c
  537. *
  538. ****************************************************************************/
  539. int nxffs_nextentry(FAR struct nxffs_volume_s *volume, off_t offset,
  540. FAR struct nxffs_entry_s *entry);
  541. /****************************************************************************
  542. * Name: nxffs_findinode
  543. *
  544. * Description:
  545. * Search for an inode with the provided name starting with the first
  546. * valid inode and proceeding to the end FLASH or until the matching
  547. * inode is found.
  548. *
  549. * Input Parameters:
  550. * volume - Describes the NXFFS volume
  551. * name - The name of the inode to find
  552. * entry - The location to return information about the inode.
  553. *
  554. * Returned Value:
  555. * Zero is returned on success. Otherwise, a negated errno is returned
  556. * that indicates the nature of the failure.
  557. *
  558. * Defined in nxffs_inode.c
  559. *
  560. ****************************************************************************/
  561. int nxffs_findinode(FAR struct nxffs_volume_s *volume, FAR const char *name,
  562. FAR struct nxffs_entry_s *entry);
  563. /****************************************************************************
  564. * Name: nxffs_inodeend
  565. *
  566. * Description:
  567. * Return an *approximiate* FLASH offset to end of the inode data. The
  568. * returned value is guaranteed to be be less then or equal to the offset
  569. * of the thing-of-interest in FLASH. Parsing for interesting things
  570. * can begin at that point.
  571. *
  572. * Assumption: The inode header has been verified by the caller and is
  573. * known to contain valid data.
  574. *
  575. * Input Parameters:
  576. * volume - Describes the NXFFS volume
  577. * entry - Describes the inode.
  578. *
  579. * Returned Value:
  580. * A FLASH offset to the (approximate) end of the inode data. No errors
  581. * are detected.
  582. *
  583. * Defined in nxffs_inode.c
  584. *
  585. ****************************************************************************/
  586. off_t nxffs_inodeend(FAR struct nxffs_volume_s *volume,
  587. FAR struct nxffs_entry_s *entry);
  588. /****************************************************************************
  589. * Name: nxffs_verifyblock
  590. *
  591. * Description:
  592. * Assure that the provided (logical) block number is in the block cache
  593. * and that it has a valid block header (i.e., proper magic and
  594. * marked good)
  595. *
  596. * Input Parameters:
  597. * volume - Describes the NXFFS volume
  598. * block - The (logical) block number to load and verify.
  599. *
  600. * Returned Value:
  601. * OK (zero( is returned on success. Otherwise, a negated errno value is
  602. * returned indicating the nature of the failure:
  603. *
  604. * -EIO is returned if we failed to read the block. If we are using
  605. * NAND memory, then this probably means that the block has
  606. * uncorrectable bit errors.
  607. * -ENOENT is returned if the block is a bad block.
  608. *
  609. * Defined in nxffs_block.c
  610. *
  611. ****************************************************************************/
  612. int nxffs_verifyblock(FAR struct nxffs_volume_s *volume, off_t block);
  613. /****************************************************************************
  614. * Name: nxffs_validblock
  615. *
  616. * Description:
  617. * Find the next valid (logical) block in the volume.
  618. *
  619. * Input Parameters:
  620. * volume - Describes the NXFFS volume
  621. * block - On entry, this provides the starting block number. If the
  622. * function is succesfful, then this memory location will hold the
  623. * block number of the next valid block on return.
  624. *
  625. * Returned Value:
  626. * Zero on success otherwise a negated errno value indicating the nature
  627. * of the failure.
  628. *
  629. * Defined in nxffs_block.c
  630. *
  631. ****************************************************************************/
  632. int nxffs_validblock(struct nxffs_volume_s *volume, off_t *block);
  633. /****************************************************************************
  634. * Name: nxffs_blockstats
  635. *
  636. * Description:
  637. * Analyze the NXFFS volume. This operation must be performed when the
  638. * volume is first mounted in order to detect if the volume has been
  639. * formatted and contains a usable NXFFS file system.
  640. *
  641. * Input Parameters:
  642. * volume - Describes the current NXFFS volume.
  643. * stats - On return, will hold nformation describing the state of the
  644. * volume.
  645. *
  646. * Returned Value:
  647. * Negated errnos are returned only in the case of MTD reported failures.
  648. * Nothing in the volume data itself will generate errors.
  649. *
  650. * Defined in nxffs_blockstats.c
  651. *
  652. ****************************************************************************/
  653. int nxffs_blockstats(FAR struct nxffs_volume_s *volume,
  654. FAR struct nxffs_blkstats_s *stats);
  655. /****************************************************************************
  656. * Name: nxffs_reformat
  657. *
  658. * Description:
  659. * Erase and reformat the entire volume. Verify each block and mark
  660. * improperly erased blocks as bad.
  661. *
  662. * Input Parameters:
  663. * volume - Describes the NXFFS volume to be reformatted.
  664. *
  665. * Returned Value:
  666. * Zero on success or a negated errno on a failure. Failures will be
  667. * returned n the case of MTD reported failures o.
  668. * Nothing in the volume data itself will generate errors.
  669. *
  670. * Defined in nxffs_reformat.c
  671. *
  672. ****************************************************************************/
  673. int nxffs_reformat(FAR struct nxffs_volume_s *volume);
  674. /****************************************************************************
  675. * Name: nxffs_blkinit
  676. *
  677. * Description:
  678. * Initialize an NXFFS block to the erased state with the specified block
  679. * status.
  680. *
  681. * Input Parameters:
  682. * volume - Describes the NXFFS volume (needed for the blocksize).
  683. * blkptr - Pointer to the logic block to initialize.
  684. * state - Either BLOCK_STATE_GOOD or BLOCK_STATE_BAD.
  685. *
  686. * Returned Value:
  687. * None.
  688. *
  689. ****************************************************************************/
  690. void nxffs_blkinit(FAR struct nxffs_volume_s *volume, FAR uint8_t *blkptr,
  691. uint8_t state);
  692. /****************************************************************************
  693. * Name: nxffs_findofile
  694. *
  695. * Description:
  696. * Search the list of already opened files to see if the inode of this
  697. * name is one of the opened files.
  698. *
  699. * Input Parameters:
  700. * volume - Describes the NXFFS volume.
  701. * name - The name of the inode to check.
  702. *
  703. * Returned Value:
  704. * If an inode of this name is found in the list of opened inodes, then
  705. * a reference to the open file structure is returned. NULL is returned
  706. * otherwise.
  707. *
  708. * Defined in nxffs_open.c
  709. *
  710. ****************************************************************************/
  711. FAR struct nxffs_ofile_s *nxffs_findofile(FAR struct nxffs_volume_s *volume,
  712. FAR const char *name);
  713. /****************************************************************************
  714. * Name: nxffs_findwriter
  715. *
  716. * Description:
  717. * Search the list of already opened files and return the open file
  718. * instance for the write.
  719. *
  720. * Input Parameters:
  721. * volume - Describes the NXFFS volume.
  722. *
  723. * Returned Value:
  724. * If there is an active writer of the volume, its open file instance is
  725. * returned. NULL is returned otherwise.
  726. *
  727. * Defined in nxffs_open.c
  728. *
  729. ****************************************************************************/
  730. FAR struct nxffs_wrfile_s *
  731. nxffs_findwriter(FAR struct nxffs_volume_s *volume);
  732. /****************************************************************************
  733. * Name: nxffs_wrinode
  734. *
  735. * Description:
  736. * Write the inode header (only to FLASH. This is done in two contexts:
  737. *
  738. * 1. When an inode is closed, or
  739. * 2. As part of the file system packing logic when an inode is moved.
  740. *
  741. * Note that in either case, the inode name has already been written to
  742. * FLASH.
  743. *
  744. * Input Parameters:
  745. * volume - Describes the NXFFS volume
  746. * entry - Describes the inode header to write
  747. *
  748. * Returned Value:
  749. * Zero is returned on success; Otherwise, a negated errno value is
  750. * returned indicating the nature of the failure.
  751. *
  752. * Defined in nxffs_open.c
  753. *
  754. ****************************************************************************/
  755. int nxffs_wrinode(FAR struct nxffs_volume_s *volume,
  756. FAR struct nxffs_entry_s *entry);
  757. /****************************************************************************
  758. * Name: nxffs_updateinode
  759. *
  760. * Description:
  761. * The packing logic has moved an inode. Check if any open files are using
  762. * this inode and, if so, move the data in the open file structure as well.
  763. *
  764. * Input Parameters:
  765. * volume - Describes the NXFFS volume
  766. * entry - Describes the new inode entry
  767. *
  768. * Returned Value:
  769. * Zero is returned on success; Otherwise, a negated errno value is
  770. * returned indicating the nature of the failure.
  771. *
  772. ****************************************************************************/
  773. int nxffs_updateinode(FAR struct nxffs_volume_s *volume,
  774. FAR struct nxffs_entry_s *entry);
  775. /****************************************************************************
  776. * Name: nxffs_wrextend
  777. *
  778. * Description:
  779. * Zero-extend a file.
  780. *
  781. * Input Parameters:
  782. * volume - Describes the NXFFS volume
  783. * entry - Describes the new inode entry
  784. * length - The new, extended length of the file
  785. *
  786. * Assumptions:
  787. * The caller holds the NXFFS semaphore.
  788. * The caller has verified that the file is writable.
  789. *
  790. ****************************************************************************/
  791. #ifdef __NO_TRUNCATE_SUPPORT__
  792. int nxffs_wrextend(FAR struct nxffs_volume_s *volume,
  793. FAR struct nxffs_wrfile_s *wrfile, off_t length);
  794. #endif
  795. /****************************************************************************
  796. * Name: nxffs_wrreserve
  797. *
  798. * Description:
  799. * Find a valid location for a file system object of 'size'. A valid
  800. * location will have these properties:
  801. *
  802. * 1. It will lie in the free flash region.
  803. * 2. It will have enough contiguous memory to hold the entire object
  804. * 3. The memory at this location will be fully erased.
  805. *
  806. * This function will only perform the checks of 1) and 2). The
  807. * end-of-filesystem offset, froffset, is update past this memory which,
  808. * in effect, reserves the memory.
  809. *
  810. * Input Parameters:
  811. * volume - Describes the NXFFS volume
  812. * size - The size of the object to be reserved.
  813. *
  814. * Returned Value:
  815. * Zero is returned on success. Otherwise, a negated errno value is
  816. * returned indicating the nature of the failure. Of special interest
  817. * the return error of -ENOSPC which means that the FLASH volume is
  818. * full and should be repacked.
  819. *
  820. * On successful return the following are also valid:
  821. *
  822. * volume->ioblock - Read/write block number of the block containing the
  823. * candidate object position
  824. * volume->iooffset - The offset in the block to the candidate object
  825. * position.
  826. * volume->froffset - Updated offset to the first free FLASH block after
  827. * the reserved memory.
  828. *
  829. * Defined in nxffs_write.c
  830. *
  831. ****************************************************************************/
  832. int nxffs_wrreserve(FAR struct nxffs_volume_s *volume, size_t size);
  833. /****************************************************************************
  834. * Name: nxffs_wrverify
  835. *
  836. * Description:
  837. * Find a valid location for the object. A valid location will have
  838. * these properties:
  839. *
  840. * 1. It will lie in the free flash region.
  841. * 2. It will have enough contiguous memory to hold the entire header
  842. * (excluding the file name which may lie in the next block).
  843. * 3. The memory at this location will be fully erased.
  844. *
  845. * This function will only perform the check 3). On entry it assumes the
  846. * following settings (left by nxffs_wrreserve()):
  847. *
  848. * volume->ioblock - Read/write block number of the block containing the
  849. * candidate object position
  850. * volume->iooffset - The offset in the block to the candidate object
  851. * position.
  852. *
  853. * Input Parameters:
  854. * volume - Describes the NXFFS volume
  855. * size - The size of the object to be verified.
  856. *
  857. * Returned Value:
  858. * Zero is returned on success. Otherwise, a negated errno value is
  859. * returned indicating the nature of the failure. Of special interest
  860. * the return error of -ENOSPC which means that the FLASH volume is
  861. * full and should be repacked.
  862. *
  863. * On successful return the following are also valid:
  864. *
  865. * volume->ioblock - Read/write block number of the block containing the
  866. * verified object position
  867. * volume->iooffset - The offset in the block to the verified object
  868. * position.
  869. * volume->froffset - Updated offset to the first free FLASH block.
  870. *
  871. * Defined in nxffs_write.c
  872. *
  873. ****************************************************************************/
  874. int nxffs_wrverify(FAR struct nxffs_volume_s *volume, size_t size);
  875. /****************************************************************************
  876. * Name: nxffs_wrblkhdr
  877. *
  878. * Description:
  879. * Write the block header information. This is done (1) whenever the end-
  880. * block is encountered and (2) also when the file is closed in order to
  881. * flush the final block of data to FLASH.
  882. *
  883. * Input Parameters:
  884. * volume - Describes the state of the NXFFS volume
  885. * wrfile - Describes the state of the open file
  886. *
  887. * Returned Value:
  888. * Zero is returned on success; Otherwise, a negated errno value is
  889. * returned to indicate the nature of the failure.
  890. *
  891. * Defined in nxffs_write.c
  892. *
  893. ****************************************************************************/
  894. int nxffs_wrblkhdr(FAR struct nxffs_volume_s *volume,
  895. FAR struct nxffs_wrfile_s *wrfile);
  896. /****************************************************************************
  897. * Name: nxffs_nextblock
  898. *
  899. * Description:
  900. * Search for the next valid data block starting at the provided
  901. * FLASH offset.
  902. *
  903. * Input Parameters:
  904. * volume - Describes the NXFFS volume.
  905. * datlen - A memory location to return the data block length.
  906. *
  907. * Returned Value:
  908. * Zero is returned on success. Otherwise, a negated errno is returned
  909. * that indicates the nature of the failure.
  910. *
  911. * Defined in nxffs_read.c
  912. *
  913. ****************************************************************************/
  914. int nxffs_nextblock(FAR struct nxffs_volume_s *volume, off_t offset,
  915. FAR struct nxffs_blkentry_s *blkentry);
  916. /****************************************************************************
  917. * Name: nxffs_rdblkhdr
  918. *
  919. * Description:
  920. * Read and verify the data block header at the specified offset.
  921. *
  922. * Input Parameters:
  923. * volume - Describes the current volume.
  924. * offset - The byte offset from the beginning of FLASH where the data
  925. * block header is expected.
  926. * datlen - A memory location to return the data block length.
  927. *
  928. * Returned Value:
  929. * Zero on success. Otherwise, a negated errno value is returned
  930. * indicating the nature of the failure.
  931. *
  932. * Defined in nxffs_read.c
  933. *
  934. ****************************************************************************/
  935. int nxffs_rdblkhdr(FAR struct nxffs_volume_s *volume, off_t offset,
  936. FAR uint16_t *datlen);
  937. /****************************************************************************
  938. * Name: nxffs_rminode
  939. *
  940. * Description:
  941. * Remove an inode from FLASH. This is the internal implementation of
  942. * the file system unlinke operation.
  943. *
  944. * Input Parameters:
  945. * volume - Describes the NXFFS volume.
  946. * name - the name of the inode to be deleted.
  947. *
  948. * Returned Value:
  949. * Zero is returned if the inode is successfully deleted. Otherwise, a
  950. * negated errno value is returned indicating the nature of the failure.
  951. *
  952. ****************************************************************************/
  953. int nxffs_rminode(FAR struct nxffs_volume_s *volume, FAR const char *name);
  954. /****************************************************************************
  955. * Name: nxffs_pack
  956. *
  957. * Description:
  958. * Pack and re-write the filesystem in order to free up memory at the end
  959. * of FLASH.
  960. *
  961. * Input Parameters:
  962. * volume - The volume to be packed.
  963. *
  964. * Returned Value:
  965. * Zero on success; Otherwise, a negated errno value is returned to
  966. * indicate the nature of the failure.
  967. *
  968. ****************************************************************************/
  969. int nxffs_pack(FAR struct nxffs_volume_s *volume);
  970. /****************************************************************************
  971. * Standard mountpoint operation methods
  972. *
  973. * Description:
  974. * See include/nuttx/fs/fs.h
  975. *
  976. * - nxffs_open() and nxffs_close() are defined in nxffs_open.c
  977. * - nxffs_read() is defined in nxffs_read.c
  978. * - nxffs_write() is defined in nxffs_write.c
  979. * - nxffs_ioctl() is defined in nxffs_ioctl.c
  980. * - nxffs_dup() is defined in nxffs_open.c
  981. * - nxffs_opendir(), nxffs_readdir(), and nxffs_rewindir() are defined in
  982. * nxffs_dirent.c
  983. * - nxffs_bind() and nxffs_unbind() are defined in nxffs_initialize.c
  984. * - nxffs_stat() and nxffs_statfs() are defined in nxffs_stat.c
  985. * - nxffs_unlink() is defined nxffs_unlink.c
  986. *
  987. ****************************************************************************/
  988. struct file; /* Forward references */
  989. struct inode;
  990. struct fs_dirent_s;
  991. struct statfs;
  992. struct stat;
  993. int nxffs_open(FAR struct file *filep, FAR const char *relpath, int oflags,
  994. mode_t mode);
  995. int nxffs_close(FAR struct file *filep);
  996. ssize_t nxffs_read(FAR struct file *filep, FAR char *buffer, size_t buflen);
  997. ssize_t nxffs_write(FAR struct file *filep, FAR const char *buffer,
  998. size_t buflen);
  999. int nxffs_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
  1000. int nxffs_dup(FAR const struct file *oldp, FAR struct file *newp);
  1001. int nxffs_fstat(FAR const struct file *filep, FAR struct stat *buf);
  1002. #ifdef __NO_TRUNCATE_SUPPORT__
  1003. int nxffs_truncate(FAR struct file *filep, off_t length);
  1004. #endif
  1005. int nxffs_opendir(FAR struct inode *mountpt, FAR const char *relpath,
  1006. FAR struct fs_dirent_s *dir);
  1007. int nxffs_readdir(FAR struct inode *mountpt, FAR struct fs_dirent_s *dir);
  1008. int nxffs_rewinddir(FAR struct inode *mountpt, FAR struct fs_dirent_s *dir);
  1009. int nxffs_bind(FAR struct inode *blkdriver, FAR const void *data,
  1010. FAR void **handle);
  1011. int nxffs_unbind(FAR void *handle, FAR struct inode **blkdriver,
  1012. unsigned int flags);
  1013. int nxffs_statfs(FAR struct inode *mountpt, FAR struct statfs *buf);
  1014. int nxffs_stat(FAR struct inode *mountpt, FAR const char *relpath,
  1015. FAR struct stat *buf);
  1016. int nxffs_unlink(FAR struct inode *mountpt, FAR const char *relpath);
  1017. #endif /* __FS_NXFFS_NXFFS_H */