summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-08-05 23:52:44 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-08-05 23:52:44 +0000
commitcd84f3dbe66739cf803208b163bda227e2fcff64 (patch)
treed4bae8e508edabfbd5dc49305699b8244a406241 /nuttx
parenta3faf4085e5b1cde0c452ac6e9125f98fd6614f3 (diff)
downloadpx4-nuttx-cd84f3dbe66739cf803208b163bda227e2fcff64.tar.gz
px4-nuttx-cd84f3dbe66739cf803208b163bda227e2fcff64.tar.bz2
px4-nuttx-cd84f3dbe66739cf803208b163bda227e2fcff64.zip
Continued mkfatfs work
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@802 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/fs/fat/Make.defs4
-rw-r--r--nuttx/fs/fat/fs_configfat.c94
-rw-r--r--nuttx/fs/fat/fs_fat32.h25
-rw-r--r--nuttx/fs/fat/fs_fat32util.c11
-rw-r--r--nuttx/fs/fat/fs_mkfatfs.h24
-rw-r--r--nuttx/fs/fat/fs_writefat.c7
6 files changed, 153 insertions, 12 deletions
diff --git a/nuttx/fs/fat/Make.defs b/nuttx/fs/fat/Make.defs
index cea6000df..3202af959 100644
--- a/nuttx/fs/fat/Make.defs
+++ b/nuttx/fs/fat/Make.defs
@@ -39,8 +39,8 @@ ifeq ($(CONFIG_FS_FAT),y)
ASRCS +=
CSRCS += fs_fat32.c fs_fat32attrib.c fs_fat32util.c
-# File required for mkfatfs utility function
+# Files required for mkfatfs utility function
ASRCS +=
-CSRCS += fs_writefat.c
+CSRCS += fs_configfat.c fs_writefat.c
endif
diff --git a/nuttx/fs/fat/fs_configfat.c b/nuttx/fs/fat/fs_configfat.c
new file mode 100644
index 000000000..2974e9f02
--- /dev/null
+++ b/nuttx/fs/fat/fs_configfat.c
@@ -0,0 +1,94 @@
+/****************************************************************************
+ * fs/fat/fs_configfat.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:
+ *
+ * Description:
+ *
+ * Input:
+ *
+ * Return:
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: mkfatfs_configfatfs
+ *
+ * Description:
+ * Based on the geometry of the block device and upon the caller-selected
+ * values, configure the FAT filesystem for the device.
+ *
+ * Input:
+ * fmt - Caller specified format parameters
+ * var - Holds disk geomtry data. Also, the location to return FAT
+ * configuration data
+ *
+ * Return:
+ * Zero on success; negated errno on failure
+ *
+ ****************************************************************************/
+int mkfatfs_configfatfs(FAR struct fat_format_s *fmt,
+ FAR struct fat_var_s *var)
+{
+ return OK;
+}
+
diff --git a/nuttx/fs/fat/fs_fat32.h b/nuttx/fs/fat/fs_fat32.h
index 3dfc0aae2..9e76f9ff9 100644
--- a/nuttx/fs/fat/fs_fat32.h
+++ b/nuttx/fs/fat/fs_fat32.h
@@ -195,6 +195,31 @@
#define FAT_BAD 0x0ffffff7
/****************************************************************************
+ * Maximum cluster by FAT type. This is the key value used to distinquish
+ * between FAT12, 16, and 32.
+ */
+
+/* FAT12: For M$, the calculation is ((1 << 12) - 19). But we will follow the
+ * Linux tradition of allowing slightly more clusters for FAT12.
+ */
+
+#define FAT_MAXCLUST12 ((1 << 12) - 16)
+
+/* FAT16: For M$, the calculation is ((1 << 16) - 19). */
+
+#define FAT_MINCLUST16 (FAT_MAXCLUST12 + 1)
+#define FAT_MAXCLUST16 ((1 << 16) - 16)
+
+/* FAT32: M$ reserves the MS 4 bits of a FAT32 FAT entry so only 18 bits are
+ * available. For M$, the calculation is ((1 << 28) - 19).
+ */
+
+#define FAT_MINCLUST32 65524
+/* #define FAT_MINCLUST32 (FAT_MAXCLUST16 + 1) */
+#define FAT_MAXCLUST32 ((1 << 28) - 16)
+
+
+/****************************************************************************
* Access to data in raw sector data */
#define UBYTE_VAL(p,o) (((ubyte*)(p))[o])
diff --git a/nuttx/fs/fat/fs_fat32util.c b/nuttx/fs/fat/fs_fat32util.c
index 2a52aa4aa..daa740ece 100644
--- a/nuttx/fs/fat/fs_fat32util.c
+++ b/nuttx/fs/fat/fs_fat32util.c
@@ -303,11 +303,12 @@ static int fat_checkbootrecord(struct fat_mountpt_s *fs)
/* Verify the FAT32 file system type. The determination of the file
* system type is based on the number of clusters on the volume: FAT12
- * volume has < 4085 cluseter, a FAT16 volume has fewer than 65,525
- * clusters, and any larger is FAT32.
+ * volume has <= FAT_MAXCLUST12 (4084) clusters, a FAT16 volume has <=
+ * FAT_MINCLUST16 (microsfoft says < 65,525) clusters, and any larger
+ * is FAT32.
*
* Get the number of 32-bit directory entries in root directory (zero
- * for FAT32.
+ * for FAT32).
*/
fs->fs_rootentcnt = MBR_GETROOTENTCNT(fs->fs_buffer);
@@ -382,12 +383,12 @@ static int fat_checkbootrecord(struct fat_mountpt_s *fs)
/* Finally, the test: */
- if (fs->fs_nclusters < 4085)
+ if (fs->fs_nclusters <= FAT_MAXCLUST12)
{
fs->fs_fsinfo = 0;
fs->fs_type = FSTYPE_FAT12;
}
- else if (fs->fs_nclusters < 65525)
+ else if (fs->fs_nclusters <= FAT_MAXCLUST16)
{
fs->fs_fsinfo = 0;
fs->fs_type = FSTYPE_FAT16;
diff --git a/nuttx/fs/fat/fs_mkfatfs.h b/nuttx/fs/fat/fs_mkfatfs.h
index 11d1848e1..c8f22d815 100644
--- a/nuttx/fs/fat/fs_mkfatfs.h
+++ b/nuttx/fs/fat/fs_mkfatfs.h
@@ -126,14 +126,34 @@ extern "C" {
#endif
/****************************************************************************
+ * Name: mkfatfs_configfatfs
+ *
+ * Description:
+ * Based on the geometry of the block device and upon the caller-selected
+ * values, configure the FAT filesystem for the device.
+ *
+ * Input:
+ * fmt - Caller specified format parameters
+ * var - Holds disk geomtry data. Also, the location to return FAT
+ * configuration data
+ *
+ * Return:
+ * Zero on success; negated errno on failure
+ *
+ ****************************************************************************/
+EXTERN int mkfatfs_configfatfs(FAR struct fat_format_s *fmt,
+ FAR struct fat_var_s *var);
+
+/****************************************************************************
* 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
+ * fmt - Caller specified format parameters
+ * var - Other format parameters that are not caller specifiable. (Most
+ * set by mkfatfs_configfatfs()).
*
* Return:
* Zero on success; negated errno on failure
diff --git a/nuttx/fs/fat/fs_writefat.c b/nuttx/fs/fat/fs_writefat.c
index 7c70c5cf6..287e4f0f8 100644
--- a/nuttx/fs/fat/fs_writefat.c
+++ b/nuttx/fs/fat/fs_writefat.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * fs/fat/fs_write.c
+ * fs/fat/fs_writefat.c
*
* Copyright (C) 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -504,8 +504,9 @@ static inline int mkfatfs_writerootdir(FAR struct fat_format_s *fmt,
* Write the configured fat filesystem to the block device
*
* Input:
- * fmt - User specified format parameters
- * var - Other format parameters that are not user specifiable
+ * fmt - Caller specified format parameters
+ * var - Other format parameters that are not caller specifiable. (Most
+ * set by mkfatfs_configfatfs()).
*
* Return:
* Zero on success; negated errno on failure