summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-08-03 17:45:20 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-08-03 17:45:20 +0000
commita3faf4085e5b1cde0c452ac6e9125f98fd6614f3 (patch)
treea2d80ca0547993f06df10e52148be66fb105acb4 /nuttx
parentad8509bd41d1ac2136d79632b2e4ac1d6aba4393 (diff)
downloadpx4-nuttx-a3faf4085e5b1cde0c452ac6e9125f98fd6614f3.tar.gz
px4-nuttx-a3faf4085e5b1cde0c452ac6e9125f98fd6614f3.tar.bz2
px4-nuttx-a3faf4085e5b1cde0c452ac6e9125f98fd6614f3.zip
fleshing out mkfatfs logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@801 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/fs/fat/Make.defs2
-rw-r--r--nuttx/fs/fat/fs_fat32.h14
-rw-r--r--nuttx/fs/fat/fs_initmbr.c211
-rw-r--r--nuttx/fs/fat/fs_mkfatfs.h60
-rw-r--r--nuttx/fs/fat/fs_writefat.c538
-rw-r--r--nuttx/include/nuttx/mkfatfs.h3
6 files changed, 598 insertions, 230 deletions
diff --git a/nuttx/fs/fat/Make.defs b/nuttx/fs/fat/Make.defs
index c9cd22a8c..cea6000df 100644
--- a/nuttx/fs/fat/Make.defs
+++ b/nuttx/fs/fat/Make.defs
@@ -42,5 +42,5 @@ CSRCS += fs_fat32.c fs_fat32attrib.c fs_fat32util.c
# File required for mkfatfs utility function
ASRCS +=
-CSRCS += fs_initmbr.c
+CSRCS += fs_writefat.c
endif
diff --git a/nuttx/fs/fat/fs_fat32.h b/nuttx/fs/fat/fs_fat32.h
index cedbd9c84..3dfc0aae2 100644
--- a/nuttx/fs/fat/fs_fat32.h
+++ b/nuttx/fs/fat/fs_fat32.h
@@ -136,7 +136,8 @@
#define DIR_WRTDATE 24 /* 2@24: Date of last write */
#define DIR_FSTCLUSTLO 26 /* 2@26: LS first cluster number */
#define DIR_FILESIZE 28 /* 4@28: File size in bytes */
-#define DIR_SIZE 32
+#define DIR_SIZE 32 /* The size of one directory entry */
+#define DIR_SHIFT 5 /* log2 of DIR_SIZE */
/* First byte of the directory name has special meanings: */
@@ -178,15 +179,22 @@
* These offset describe the FSINFO sector
*/
-#define FSI_LEADSIG 0 /* 4@0: 0x41615252 */
+#define FSI_LEADSIG 0 /* 4@0: 0x41615252 = "RRaA" */
/* 480@4: Reserved (zero) */
-#define FSI_STRUCTSIG 484 /* 4@484: 0x61417272 */
+#define FSI_STRUCTSIG 484 /* 4@484: 0x61417272 = "rrAa" */
#define FSI_FREECOUNT 488 /* 4@488: Last free cluster count on volume */
#define FSI_NXTFREE 492 /* 4@492: Cluster number of 1st free cluster */
/* 12@496: Reserved (zero) */
#define FSI_TRAILSIG 508 /* 4@508: 0xaa550000 */
/****************************************************************************
+ * FAT values
+ */
+
+#define FAT_EOF 0x0ffffff8
+#define FAT_BAD 0x0ffffff7
+
+/****************************************************************************
* Access to data in raw sector data */
#define UBYTE_VAL(p,o) (((ubyte*)(p))[o])
diff --git a/nuttx/fs/fat/fs_initmbr.c b/nuttx/fs/fat/fs_initmbr.c
deleted file mode 100644
index 3d9e30430..000000000
--- a/nuttx/fs/fat/fs_initmbr.c
+++ /dev/null
@@ -1,211 +0,0 @@
-/****************************************************************************
- * fs/fat/fs_initmbr.c
- *
- * Copyright (C) 2008 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-#include <sys/types.h>
-
-#include <string.h>
-#include <errno.h>
-
-#include <nuttx/fs.h>
-#include <nuttx/fat.h>
-#include <nuttx/mkfatfs.h>
-
-#include "fs_internal.h"
-#include "fs_fat32.h"
-#include "fs_mkfatfs.h"
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Global Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: mkfatfs_initmbr
- *
- * Description:
- * Initialize the sector image of a masterbood record
- *
- * Input:
- * fmt - User specified format parameters
- * var - Other format parameters that are not user specifiable
- * sect - Allocated memory to hold the MBR
- *
- * Return:
- * None; caller is responsible for providing valid parameters.
- *
- ****************************************************************************/
-void mkfatfs_initmbr(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var, ubyte *sect)
-{
- memset(sect, 0, var->fv_sectorsize);
-
- /* 3@0: Jump instruction to boot code */
-
- memcpy(&sect[BS_JUMP], var->fv_jump, 3);
-
- /* 8@3: Usually "MSWIN4.1" */
-
- strcpy(&sect[BS_OEMNAME], "NUTTX ");
-
- /* 2@11: Bytes per sector: 512, 1024, 2048, 4096 */
-
- MBR_PUTBYTESPERSEC(sect, var->fv_sectorsize);
-
- /* 1@13: Sectors per allocation unit: 2**n, n=0..7 */
-
- MBR_PUTSECPERCLUS(sect, fmt->ff_clustsize);
-
- /* 2@14: Reserved sector count: Usually 32 */
-
- MBR_PUTRESVDSECCOUNT(sect, fmt->ff_rsvdseccount);
-
- /* 1@16: Number of FAT data structures: always 2 */
-
- MBR_PUTNUMFATS(sect, fmt->ff_nfats);
-
- /* 2@17: FAT12/16: Must be 0 for FAT32 */
-
- MBR_PUTROOTENTCNT(sect, fmt->ff_rootdirentries);
-
- /* 2@19: FAT12/16: Must be 0, see BS_TOTSEC32. Handled with 4@32: Total count of sectors on the volume */
-
- if (var->fv_nsectors >= 65536)
- {
- MBR_PUTTOTSEC32(sect, var->fv_nsectors);
- }
- else
- {
- MBR_PUTTOTSEC16(sect, (uint16)var->fv_nsectors);
- }
-
- /* 1@21: Media code: f0, f8, f9-fa, fc-ff */
-
- MBR_PUTMEDIA(sect, FAT_DEFAULT_MEDIA_TYPE); /* Only "hard drive" supported */
-
- /* 2@22: FAT12/16: Must be 0, see BS32_FATSZ32 -- handled in FAT specific logic */
-
- /* 2@24: Sectors per track geometry value and 2@26: Number of heads geometry value */
-
- MBR_PUTSECPERTRK(sect, FAT_DEFAULT_SECPERTRK);
- MBR_PUTNUMHEADS(sect, FAT_DEFAULT_NUMHEADS);
-
- /* 4@28: Count of hidden sectors preceding FAT */
-
- MBR_PUTHIDSEC(sect, fmt->ff_hidsec);
-
- /* 4@32: Total count of sectors on the volume -- handled above */
-
- /* Most of the rest of the sector depends on the FAT size */
-
- if (fmt->ff_fatsize != 32)
- {
- /* 2@22: FAT12/16: Must be 0, see BS32_FATSZ32 */
-
- MBR_PUTFATSZ16(sect, (uint16)var->fv_fatlen);
-
- /* The following fields are only valid for FAT12/16 */
- /* 1@36: Drive number for MSDOS bootstrap -- left zero */
- /* 1@37: Reserved (zero) */
- /* 1@38: Extended boot signature: 0x29 if following valid */
-
- MBR_PUTBOOTSIG16(sect, EXTBOOT_SIGNATURE);
-
- /* 4@39: Volume serial number */
-
- MBR_PUTVOLID16(sect, fmt->ff_volumeid);
-
- /* 11@43: Volume label */
-
- memcpy(&sect[BS16_VOLLAB], fmt->ff_volumelabel, 11);
-
- /* 8@54: "FAT12 ", "FAT16 ", or "FAT " */
- /* Boot code may be placed in the remainder of the sector */
-
- memcpy(&sect[BS16_BOOTCODE], var->fv_bootcode, var->fv_bootcodesize);
- }
- else
- {
- /* The following fields are only valid for FAT32 */
- /* 4@36: Count of sectors occupied by one FAT */
-
- MBR_PUTFATSZ32(sect, var->fv_fatlen);
-
- /* 2@40: 0-3:Active FAT, 7=0 both FATS, 7=1 one FAT -- left zero*/
- /* 2@42: MSB:Major LSB:Minor revision number (0.0) -- left zero */
- /* 4@44: Cluster no. of 1st cluster of root dir */
-
- MBR_PUTROOTCLUS(sect, FAT32_DEFAULT_ROOT_CLUSTER);
-
- /* 2@48: Sector number of fsinfo structure. Usually 1. */
-
- MBR_PUTFSINFO(sect, FAT_DEFAULT_FSINFO_SECTOR);
-
- /* 2@50: Sector number of boot record. Usually 6 */
-
- MBR_PUTBKBOOTSEC(sect, fmt->ff_backupboot);
-
- /* 12@52: Reserved (zero) */
- /* 1@64: Drive number for MSDOS bootstrap -- left zero */
- /* 1@65: Reserved (zero) */
- /* 1@66: Extended boot signature: 0x29 if following valid */
-
- MBR_PUTBOOTSIG32(sect, EXTBOOT_SIGNATURE);
-
- /* 4@67: Volume serial number */
-
- MBR_PUTVOLID32(sect, fmt->ff_volumeid);
-
- /* 11@71: Volume label */
-
- memcpy(&sect[BS32_VOLLAB], fmt->ff_volumelabel, 11);
-
- /* 8@82: "FAT12 ", "FAT16 ", or "FAT " */
- /* Boot code may be placed in the remainder of the sector */
-
- memcpy(&sect[BS16_BOOTCODE], var->fv_bootcode, var->fv_bootcodesize);
- }
-
- /* The magic bytes at the end of the MBR are common to FAT12/16/32 */
- /* 2@510: Valid MBRs have 0x55aa here */
-
- MBR_PUTSIGNATURE(sect, BOOT_SIGNATURE16);
-}
diff --git a/nuttx/fs/fat/fs_mkfatfs.h b/nuttx/fs/fat/fs_mkfatfs.h
index 84ddfe28f..11d1848e1 100644
--- a/nuttx/fs/fat/fs_mkfatfs.h
+++ b/nuttx/fs/fat/fs_mkfatfs.h
@@ -64,6 +64,25 @@
#define FAT32_DEFAULT_ROOT_CLUSTER 2
+/* Macros to simplify direct block driver access */
+
+#define DEV_OPEN() \
+ var->fb_inode->u.i_bops->open ? \
+ var->fv_inode->u.i_bops->open(var->fv_inode) : \
+ 0
+#define DEV_CLOSE() \
+ var->fb_inode->u.i_bops->close ? \
+ var->fv_inode->u.i_bops->close(var->fv_inode) : \
+ 0
+#define DEV_READ(buf, sect, nsect) \
+ var->fv_inode->u.i_bops->read(var->fv_inode, buf, sect, nsect)
+#define DEV_WRITE(buf, sect, nsect) \
+ var->fv_inode->u.i_bops->write(var->fv_inode, buf, sect, nsect)
+#define DEV_GEOMETRY(geo) \
+ var->fv_inode->u.i_bops->geometry(var->fv_inode, &geo)
+#define DEV_IOCTL(cmd, arg) \
+ var->fv_inode->u.i_bops->ioctl(var->fv_inode, cmd, arg)
+
/****************************************************************************
* Public Types
****************************************************************************/
@@ -76,17 +95,18 @@
struct fat_var_s
{
- ubyte fv_jump[3]; /* 3-byte boot jump instruction */
- ubyte fv_sectshift; /* Log2 of fv_sectorsize */
- uint16 fv_bootcodesize; /* Size of array at fv_bootcode */
- uint32 fv_createtime; /* Creation time */
- uint32 fv_sectorsize; /* Size of one hardware sector */
- uint32 fv_nsectors; /* Number of sectors */
- uint32 fv_fatlen; /* Size of the FAT */
- ubyte *fv_rootdir; /* Allocated root directory sector */
- ubyte *fv_mbr; /* Allocated master boot record image */
- ubyte *fv_info; /* FAT32 info sector */
- const ubyte *fv_bootcode; /* Points to boot code to put into MBR */
+ struct inode *fv_inode; /* The block driver "handle" */
+ ubyte fv_jump[3]; /* 3-byte boot jump instruction */
+ ubyte fv_sectshift; /* Log2 of fv_sectorsize */
+ ubyte fv_nrootdirsects; /* Number of root directory sectors */
+ uint16 fv_bootcodesize; /* Size of array at fv_bootcode */
+ uint32 fv_createtime; /* Creation time */
+ uint32 fv_sectorsize; /* Size of one hardware sector */
+ uint32 fv_nsectors; /* Number of sectors */
+ uint32 fv_nfatsects; /* Number of sectors in each FAT */
+ uint32 fv_clustcount; /* Number of clusters */
+ ubyte *fv_sect; /* Allocated working sector buffer */
+ const ubyte *fv_bootcode; /* Points to boot code to put into MBR */
};
/****************************************************************************
@@ -105,8 +125,22 @@ extern "C" {
#define EXTERN extern
#endif
-EXTERN void mkfatfs_initmbr(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var, ubyte *sect)
-;
+/****************************************************************************
+ * Name: mkfatfs_writefat
+ *
+ * Description:
+ * Write the configured fat filesystem to the block device
+ *
+ * Input:
+ * fmt - User specified format parameters
+ * var - Other format parameters that are not user specifiable
+ *
+ * Return:
+ * Zero on success; negated errno on failure
+ *
+ ****************************************************************************/
+EXTERN int mkfatfs_writefatfs(FAR struct fat_format_s *fmt,
+ FAR struct fat_var_s *var);
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/fs/fat/fs_writefat.c b/nuttx/fs/fat/fs_writefat.c
new file mode 100644
index 000000000..7c70c5cf6
--- /dev/null
+++ b/nuttx/fs/fat/fs_writefat.c
@@ -0,0 +1,538 @@
+/****************************************************************************
+ * fs/fat/fs_write.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+
+#include <string.h>
+#include <errno.h>
+
+#include <nuttx/fs.h>
+#include <nuttx/fat.h>
+#include <nuttx/mkfatfs.h>
+
+#include "fs_internal.h"
+#include "fs_fat32.h"
+#include "fs_mkfatfs.h"
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: mkfatfs_initmbr
+ *
+ * Description:
+ * Initialize the sector image of a masterbood record
+ *
+ * Input:
+ * fmt - User specified format parameters
+ * var - Other format parameters that are not user specifiable
+ *
+ * Return:
+ * None; caller is responsible for providing valid parameters.
+ *
+ ****************************************************************************/
+static inline void mkfatfs_initmbr(FAR struct fat_format_s *fmt,
+ FAR struct fat_var_s *var)
+{
+ memset(var->fv_sect, 0, var->fv_sectorsize);
+
+ /* 3@0: Jump instruction to boot code */
+
+ memcpy(&var->fv_sect[BS_JUMP], var->fv_jump, 3);
+
+ /* 8@3: Usually "MSWIN4.1" */
+
+ strcpy(&var->fv_sect[BS_OEMNAME], "NUTTX ");
+
+ /* 2@11: Bytes per sector: 512, 1024, 2048, 4096 */
+
+ MBR_PUTBYTESPERSEC(var->fv_sect, var->fv_sectorsize);
+
+ /* 1@13: Sectors per allocation unit: 2**n, n=0..7 */
+
+ MBR_PUTSECPERCLUS(var->fv_sect, fmt->ff_clustsize);
+
+ /* 2@14: Reserved sector count: Usually 32 */
+
+ MBR_PUTRESVDSECCOUNT(var->fv_sect, fmt->ff_rsvdseccount);
+
+ /* 1@16: Number of FAT data structures: always 2 */
+
+ MBR_PUTNUMFATS(var->fv_sect, fmt->ff_nfats);
+
+ /* 2@17: FAT12/16: Must be 0 for FAT32 */
+
+ MBR_PUTROOTENTCNT(var->fv_sect, fmt->ff_rootdirentries);
+
+ /* 2@19: FAT12/16: Must be 0, see BS_TOTSEC32.
+ * Handled with 4@32: Total count of sectors on the volume */
+
+ if (var->fv_nsectors >= 65536)
+ {
+ MBR_PUTTOTSEC32(var->fv_sect, var->fv_nsectors);
+ }
+ else
+ {
+ MBR_PUTTOTSEC16(var->fv_sect, (uint16)var->fv_nsectors);
+ }
+
+ /* 1@21: Media code: f0, f8, f9-fa, fc-ff */
+
+ MBR_PUTMEDIA(var->fv_sect, FAT_DEFAULT_MEDIA_TYPE); /* Only "hard drive" supported */
+
+ /* 2@22: FAT12/16: Must be 0, see BS32_FATSZ32 -- handled in FAT specific logic */
+
+ /* 2@24: Sectors per track geometry value and 2@26: Number of heads geometry value */
+
+ MBR_PUTSECPERTRK(var->fv_sect, FAT_DEFAULT_SECPERTRK);
+ MBR_PUTNUMHEADS(var->fv_sect, FAT_DEFAULT_NUMHEADS);
+
+ /* 4@28: Count of hidden sectors preceding FAT */
+
+ MBR_PUTHIDSEC(var->fv_sect, fmt->ff_hidsec);
+
+ /* 4@32: Total count of sectors on the volume -- handled above */
+
+ /* Most of the rest of the sector depends on the FAT size */
+
+ if (fmt->ff_fatsize != 32)
+ {
+ /* 2@22: FAT12/16: Must be 0, see BS32_FATSZ32 */
+
+ MBR_PUTFATSZ16(var->fv_sect, (uint16)var->fv_nfatsects);
+
+ /* The following fields are only valid for FAT12/16 */
+ /* 1@36: Drive number for MSDOS bootstrap -- left zero */
+ /* 1@37: Reserved (zero) */
+ /* 1@38: Extended boot signature: 0x29 if following valid */
+
+ MBR_PUTBOOTSIG16(var->fv_sect, EXTBOOT_SIGNATURE);
+
+ /* 4@39: Volume serial number */
+
+ MBR_PUTVOLID16(var->fv_sect, fmt->ff_volumeid);
+
+ /* 11@43: Volume label */
+
+ memcpy(&var->fv_sect[BS16_VOLLAB], fmt->ff_volumelabel, 11);
+
+ /* 8@54: "FAT12 ", "FAT16 ", or "FAT " */
+
+ if (fmt->ff_fatsize == 12)
+ {
+ memcpy(&var->fv_sect[BS16_FILESYSTYPE], "FAT12 ", 8);
+ }
+ else /* if (fmt->ff_fatsize == 16) */
+ {
+ memcpy(&var->fv_sect[BS16_FILESYSTYPE], "FAT16 ", 8);
+ }
+
+ /* Boot code may be placed in the remainder of the sector */
+
+ memcpy(&var->fv_sect[BS16_BOOTCODE], var->fv_bootcode, var->fv_bootcodesize);
+ }
+ else
+ {
+ /* The following fields are only valid for FAT32 */
+ /* 4@36: Count of sectors occupied by one FAT */
+
+ MBR_PUTFATSZ32(var->fv_sect, var->fv_nfatsects);
+
+ /* 2@40: 0-3:Active FAT, 7=0 both FATS, 7=1 one FAT -- left zero*/
+ /* 2@42: MSB:Major LSB:Minor revision number (0.0) -- left zero */
+ /* 4@44: Cluster no. of 1st cluster of root dir */
+
+ MBR_PUTROOTCLUS(var->fv_sect, FAT32_DEFAULT_ROOT_CLUSTER);
+
+ /* 2@48: Sector number of fsinfo structure. Usually 1. */
+
+ MBR_PUTFSINFO(var->fv_sect, FAT_DEFAULT_FSINFO_SECTOR);
+
+ /* 2@50: Sector number of boot record. Usually 6 */
+
+ MBR_PUTBKBOOTSEC(var->fv_sect, fmt->ff_backupboot);
+
+ /* 12@52: Reserved (zero) */
+ /* 1@64: Drive number for MSDOS bootstrap -- left zero */
+ /* 1@65: Reserved (zero) */
+ /* 1@66: Extended boot signature: 0x29 if following valid */
+
+ MBR_PUTBOOTSIG32(var->fv_sect, EXTBOOT_SIGNATURE);
+
+ /* 4@67: Volume serial number */
+
+ MBR_PUTVOLID32(var->fv_sect, fmt->ff_volumeid);
+
+ /* 11@71: Volume label */
+
+ memcpy(&var->fv_sect[BS32_VOLLAB], fmt->ff_volumelabel, 11);
+
+ /* 8@82: "FAT12 ", "FAT16 ", or "FAT " */
+
+ memcpy(&var->fv_sect[BS32_FILESYSTYPE], "FAT32 ", 8);
+
+ /* Boot code may be placed in the remainder of the sector */
+
+ memcpy(&var->fv_sect[BS16_BOOTCODE], var->fv_bootcode, var->fv_bootcodesize);
+ }
+
+ /* The magic bytes at the end of the MBR are common to FAT12/16/32 */
+ /* 2@510: Valid MBRs have 0x55aa here */
+
+ MBR_PUTSIGNATURE(var->fv_sect, BOOT_SIGNATURE16);
+}
+
+/****************************************************************************
+ * Name: mkfatfs_initfsinfo
+ *
+ * Description:
+ * Initialize the FAT32 FSINFO sector image
+ *
+ * Input:
+ * fmt - User specified format parameters
+ * var - Other format parameters that are not user specifiable
+ *
+ * Return:
+ * None; caller is responsible for providing valid parameters.
+ *
+ ****************************************************************************/
+static inline void mkfatfs_initfsinfo(FAR struct fat_format_s *fmt,
+ FAR struct fat_var_s *var)
+{
+ memset(var->fv_sect, 0, var->fv_sectorsize);
+
+ /* 4@0: 0x41615252 = "RRaA" */
+
+ FSI_PUTLEADSIG(var->fv_sect, 0x41615252);
+
+ /* 480@4: Reserved (zero) */
+ /* 4@484: 0x61417272 = "rrAa" */
+
+ FSI_PUTSTRUCTSIG(var->fv_sect, 0x61417272);
+
+ /* 4@488: Last free cluster count on volume */
+
+ FSI_PUTFREECOUNT(var->fv_sect, var->fv_clustcount - 1);
+
+ /* 4@492: Cluster number of 1st free cluster */
+
+ FSI_PUTNXTFREE(var->fv_sect, FAT32_DEFAULT_ROOT_CLUSTER);
+
+ /* 12@496: Reserved (zero) */
+ /* 4@508: 0xaa550000 */
+
+ FSI_PUTTRAILSIG(var->fv_sect, BOOT_SIGNATURE32);
+}
+
+/****************************************************************************
+ * Name: mkfatfs_initrootdir
+ *
+ * Description:
+ * Initialize one root directory sector image
+ *
+ * Input:
+ * fmt - User specified format parameters
+ * var - Other format parameters that are not user specifiable
+ * sectno - On FAT32, the root directory is a cluster chain.
+ * This value indicates which sector of the cluster should be produced.
+ *
+ * Return:
+ * None; caller is responsible for providing valid parameters.
+ *
+ ****************************************************************************/
+static inline void mkfatfs_initrootdir(FAR struct fat_format_s *fmt,
+ FAR struct fat_var_s *var, int sectno)
+{
+ memset(var->fv_sect, 0, var->fv_sectorsize);
+ if (sectno == 0)
+ {
+ /* It is only necessary to set data in the first sector of the directory */
+
+ if (memcmp(fmt->ff_volumelabel, " ", 11))
+ {
+ memcpy(&var->fv_sect[DIR_NAME], fmt->ff_volumelabel, 11);
+ }
+
+ DIR_PUTATTRIBUTES(var->fv_sect, FATATTR_VOLUMEID);
+ DIR_PUTCRTIME(var->fv_sect, var->fv_createtime & 0xffff);
+ DIR_PUTWRTTIME(var->fv_sect, var->fv_createtime & 0xffff);
+ DIR_PUTCRDATE(var->fv_sect, var->fv_createtime >> 16);
+ DIR_PUTWRTDATE(var->fv_sect, var->fv_createtime >> 16);
+ }
+}
+
+/****************************************************************************
+ * Name: mkfatfs_writembr
+ *
+ * Description:
+ * Write the master boot record and, for FAT32, the backup boot record and
+ * the fsinfo sector.
+ *
+ * Input:
+ * fmt - User specified format parameters
+ * var - Other format parameters that are not user specifiable
+ *
+ * Return:
+ * Zero on success; negated errno on failure
+ *
+ ****************************************************************************/
+static inline int mkfatfs_writembr(FAR struct fat_format_s *fmt,
+ FAR struct fat_var_s *var)
+{
+ int sectno;
+ int ret;
+
+ /* Create an image of the configured master boot record */
+
+ mkfatfs_initmbr(fmt, var);
+
+ /* Write the master boot record as sector zero */
+
+ ret = DEV_WRITE(var->fv_sect, 0, 1);
+
+ /* Write all of the reserved sectors */
+
+ memset(var->fv_sect, 0, var->fv_sectorsize);
+ for (sectno = 1; sectno < fmt->ff_rsvdseccount && ret >= 0; sectno++)
+ {
+ ret = DEV_WRITE(var->fv_sect, sectno, 1);
+ }
+
+ /* Write FAT32-specific sectors */
+
+ if (ret >= 0 && fmt->ff_fatsize == 32)
+ {
+ /* Write the backup master boot record */
+
+ if (fmt->ff_backupboot != 0)
+ {
+ /* Create another copy of the configured master boot record */
+
+ mkfatfs_initmbr(fmt, var);
+
+ /* Write it to the backup location */
+
+ ret = DEV_WRITE(var->fv_sect, fmt->ff_backupboot, 1);
+ }
+
+ if (ret >= 0)
+ {
+ /* Create an image of the fsinfo sector*/
+
+ mkfatfs_initfsinfo(fmt, var);
+
+ /* Write the fsinfo sector */
+
+ ret = DEV_WRITE(var->fv_sect, FAT_DEFAULT_FSINFO_SECTOR, 1);
+ }
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Name: mkfatfs_writefat
+ *
+ * Description:
+ * Write the FAT sectors
+ *
+ * Input:
+ * fmt - User specified format parameters
+ * var - Other format parameters that are not user specifiable
+ *
+ * Return:
+ * Zero on success; negated errno on failure
+ *
+ ****************************************************************************/
+static inline int mkfatfs_writefat(FAR struct fat_format_s *fmt,
+ FAR struct fat_var_s *var)
+{
+ size_t offset = fmt->ff_rsvdseccount;
+ int fatno;
+ int sectno;
+ int ret;
+
+ /* Loop for each FAT copy */
+
+ for (fatno = 0; fatno < fmt->ff_nfats; fatno++)
+ {
+ /* Loop for each sector in the FAT */
+
+ for (sectno = 0; sectno < var->fv_nfatsects; sectno++)
+ {
+ memset(var->fv_sect, 0, var->fv_sectorsize);
+
+ /* Mark cluster allocations in sector one of each FAT */
+
+ if (sectno == 0)
+ {
+ memset(var->fv_sect, 0, var->fv_sectorsize);
+ switch(fmt->ff_fatsize)
+ {
+ case 12:
+ /* Mark the first two full FAT entries -- 24 bits, 3 bytes total */
+
+ memset(var->fv_sect, 0xff, 3);
+ break;
+
+ case 16:
+ /* Mark the first two full FAT entries -- 32 bits, 4 bytes total */
+
+ memset(var->fv_sect, 0xff, 4);
+ break;
+
+ case 32:
+ default: /* Shouldn't happen */
+ /* Mark the first two full FAT entries -- 64 bits, 8 bytes total */
+
+ memset(var->fv_sect, 0xff, 8);
+
+ /* Cluster 2 is used as the root directory. Mark as EOF */
+
+ var->fv_sect[8] = 0xf8;
+ memset(&var->fv_sect[9], 0xff, 3);
+ break;
+ }
+
+ /* Save the media type in the first byte of the FAT */
+
+ var->fv_sect[0] = FAT_DEFAULT_MEDIA_TYPE;
+ }
+
+ /* Write the FAT sector */
+
+ ret = DEV_WRITE(var->fv_sect, offset, 1);
+ if (ret < 0)
+ {
+ return ret;
+ }
+ offset++;
+ }
+ }
+ return OK;
+}
+
+/****************************************************************************
+ * Name: mkfatfs_writerootdir
+ *
+ * Description:
+ * Write the root directory sectors
+ *
+ * Input:
+ * fmt - User specified format parameters
+ * var - Other format parameters that are not user specifiable
+ *
+ * Return:
+ * Zero on success; negated errno on failure
+ *
+ ****************************************************************************/
+static inline int mkfatfs_writerootdir(FAR struct fat_format_s *fmt,
+ FAR struct fat_var_s *var)
+{
+ size_t offset = fmt->ff_rsvdseccount + fmt->ff_nfats * var->fv_nfatsects;
+ int ret;
+ int i;
+
+ /* Write the root directory after the last FAT. This is the root directory
+ * area for FAT12/16, and the first cluster on FAT32.
+ */
+
+ for (i = 0; i < var->fv_nrootdirsects; i++)
+ {
+ /* Format the next sector of the root directory */
+
+ mkfatfs_initrootdir(fmt, var, i);
+
+ /* Write the next sector of the root directory */
+
+ ret = DEV_WRITE(var->fv_sect, offset, 1);
+ if (ret < 0)
+ {
+ return ret;
+ }
+ offset++;
+ }
+ return 0;
+}
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: mkfatfs_writefat
+ *
+ * Description:
+ * Write the configured fat filesystem to the block device
+ *
+ * Input:
+ * fmt - User specified format parameters
+ * var - Other format parameters that are not user specifiable
+ *
+ * Return:
+ * Zero on success; negated errno on failure
+ *
+ ****************************************************************************/
+int mkfatfs_writefatfs(FAR struct fat_format_s *fmt,
+ FAR struct fat_var_s *var)
+{
+ int ret;
+
+ /* Write the master boot record (also the backup and fsinfo sectors) */
+
+ ret = mkfatfs_writembr(fmt, var);
+
+ /* Write FATs */
+
+ if (ret >= 0)
+ {
+ ret = mkfatfs_writefat(fmt, var);
+ }
+
+ /* Write the root directory after the last FAT. */
+
+ if (ret >= 0)
+ {
+ ret = mkfatfs_writerootdir(fmt, var);
+ }
+ return ret;
+}
+
diff --git a/nuttx/include/nuttx/mkfatfs.h b/nuttx/include/nuttx/mkfatfs.h
index 0952881cd..c0ca82280 100644
--- a/nuttx/include/nuttx/mkfatfs.h
+++ b/nuttx/include/nuttx/mkfatfs.h
@@ -84,7 +84,6 @@
struct fat_format_s
{
- boolean ff_bbcheck; /* TRUE: check for bad blocks */
ubyte ff_nfats; /* Number of FATs */
ubyte ff_fatsize; /* FAT size: 0 (autoselect), 12, 16, or 32 */
ubyte ff_clustsize; /* Number of sectors per cluster: 0 (autoselect) */
@@ -130,7 +129,7 @@ extern "C" {
* size in 'fmt', bad cluster size in 'fmt'
* ENOENT - 'pathname' does not refer to anything in the filesystem.
* ENOTBLK - 'pathname' does not refer to a block driver
- * ENOSPC - block driver does not support geometry method
+ * EACCESS - block driver does not support wrie or geometry methods
*
* Assumptions:
* - The caller must assure that the block driver is not mounted and not in