From 6caaa80d431e0c01f2f1197315516cae71792b52 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 9 Aug 2008 21:48:06 +0000 Subject: Implemented mkfatfs() git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@805 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/fs/fat/Make.defs | 2 +- nuttx/fs/fat/fs_configfat.c | 307 +++++++++++++++++++++++++++++++++---------- nuttx/fs/fat/fs_mkfatfs.c | 311 ++++++++++++++++++++++++++++++++++++++++++++ nuttx/fs/fat/fs_mkfatfs.h | 1 - nuttx/fs/fat/fs_writefat.c | 6 +- 5 files changed, 555 insertions(+), 72 deletions(-) create mode 100644 nuttx/fs/fat/fs_mkfatfs.c (limited to 'nuttx/fs') diff --git a/nuttx/fs/fat/Make.defs b/nuttx/fs/fat/Make.defs index 3202af959..2f1a01003 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 # Files required for mkfatfs utility function ASRCS += -CSRCS += fs_configfat.c fs_writefat.c +CSRCS += fs_mkfatfs.c fs_configfat.c fs_writefat.c endif diff --git a/nuttx/fs/fat/fs_configfat.c b/nuttx/fs/fat/fs_configfat.c index 50d130e29..d69c483ad 100644 --- a/nuttx/fs/fat/fs_configfat.c +++ b/nuttx/fs/fat/fs_configfat.c @@ -64,6 +64,13 @@ #define fatconfig16 fatconfig[NDX16] #define fatconfig32 fatconfig[NDX32] +/* JMP rel8 and NOP opcodes */ + +#define OPCODE_JMP_REL8 0xeb +#define OPCODE_NOP 0x90 + +#define BOOTCODE_MSGOFFSET 29 + /**************************************************************************** * Private Types ****************************************************************************/ @@ -73,12 +80,34 @@ struct fat_config_s uint32 fc_navailsects; /* The number of available sectors */ uint32 fc_nfatsects; /* The number of sectors in one FAT */ uint32 fc_nclusters; /* The number of clusters in the filesystem */ + uint32 fc_rsvdseccount; /* The number of reserved sectors */ }; /**************************************************************************** * Private Data ****************************************************************************/ +/* Reverse engineered, generic boot message logic for non-bootable disk. + * Message begins at offset 29; Sector relative offset must be poked into + * offset 3. + */ + +static ubyte g_bootcodeblob[] = +{ + 0x0e, 0x1f, 0xbe, 0x00, 0x7c, 0xac, 0x22, 0xc0, 0x74, 0x0b, 0x56, + 0xb4, 0x0e, 0xbb, 0x07, 0x00, 0xcd, 0x10, 0x5e, 0xeb, 0xf0, 0x32, + 0xe4, 0xcd, 0x16, 0xcd, 0x19, 0xeb, 0xfe, 0x54, 0x68, 0x69, 0x73, + 0x20, 0x69, 0x73, 0x20, 0x6e, 0x6f, 0x74, 0x20, 0x61, 0x20, 0x62, + 0x6f, 0x6f, 0x74, 0x61, 0x62, 0x6c, 0x65, 0x20, 0x64, 0x69, 0x73, + 0x6b, 0x2e, 0x20, 0x20, 0x50, 0x6c, 0x65, 0x61, 0x73, 0x65, 0x20, + 0x69, 0x6e, 0x73, 0x65, 0x72, 0x74, 0x20, 0x61, 0x20, 0x62, 0x6f, + 0x6f, 0x74, 0x61, 0x62, 0x6c, 0x65, 0x20, 0x66, 0x6c, 0x6f, 0x70, + 0x70, 0x79, 0x20, 0x61, 0x6e, 0x64, 0x0d, 0x0a, 0x70, 0x72, 0x65, + 0x73, 0x73, 0x20, 0x61, 0x6e, 0x79, 0x20, 0x6b, 0x65, 0x79, 0x20, + 0x74, 0x6f, 0x20, 0x74, 0x72, 0x79, 0x20, 0x61, 0x67, 0x61, 0x69, + 0x6e, 0x20, 0x2e, 0x2e, 0x2e, 0x0d, 0x0a, 0x00 +}; + /**************************************************************************** * Private Functions ****************************************************************************/ @@ -307,27 +336,27 @@ mkfatfs_clustersearchlimits(FAR struct fat_format_s *fmt, FAR struct fat_var_s * { /* Pick a starting size based on the number of sectors on the device */ - if (var->fv_nsectors < 2048) + if (fmt->ff_nsectors < 2048) { /* 2k sectors, start wit 1 sector/cluster. */ fmt->ff_clustshift = 0; } - else if (var->fv_nsectors < 4096) + else if (fmt->ff_nsectors < 4096) { /* 4k sectors, start with 2 sector/cluster. */ fmt->ff_clustshift = 1; } - else if (var->fv_nsectors < 8192) + else if (fmt->ff_nsectors < 8192) { /* 8k sectors, start with 4 sector/cluster. */ fmt->ff_clustshift = 2; } - else if (var->fv_nsectors < 16384) + else if (fmt->ff_nsectors < 16384) { /* 16k sectors, start with 8 sector/cluster. */ fmt->ff_clustshift = 3; } - else if (var->fv_nsectors < 32768) + else if (fmt->ff_nsectors < 32768) { /* 32k sectors, start with 16 sector/cluster. */ fmt->ff_clustshift = 4; @@ -559,6 +588,35 @@ mkfatfs_tryfat32(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var, return 0; } +/**************************************************************************** + * Name: mkfatfs_selectfat + * + * Description: + * The cluster search has succeeded, select the specified FAT FS + * + * Input: + * fattype - The FAT size selected + * fmt - Caller specified format parameters + * var - Format parameters that are not caller specifiable. + * + * Return: + * None + * + ****************************************************************************/ + +static inline void +mkfatfs_selectfat(int fattype, FAR struct fat_format_s *fmt, + FAR struct fat_var_s *var, FAR struct fat_config_s *config) +{ + /* Return the appropriate information about the selected file system. */ + + fdbg("Selected FAT%d\n", fattype); + var->fv_fattype = fattype; + var->fv_nclusters = config->fc_nclusters; + var->fv_nfatsects = config->fc_nfatsects; + fmt->ff_rsvdseccount = config->fc_rsvdseccount; +} + /**************************************************************************** * Name: mkfatfs_clustersearch * @@ -580,11 +638,34 @@ static inline int mkfatfs_clustersearch(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var) { struct fat_config_s fatconfig[3]; - uint32 nrootdirsects = 0; ubyte mxclustshift; memset(fatconfig, 0, 3*sizeof(struct fat_config_s)); + /* Select the reserved sector count for each FAT size */ + + if (fmt->ff_rsvdseccount) + { + fatconfig12.fc_rsvdseccount = fmt->ff_rsvdseccount; + fatconfig16.fc_rsvdseccount = fmt->ff_rsvdseccount; + + if (fmt->ff_rsvdseccount < 2) + { + fvdbg("At least 2 reserved sectors needed by FAT32\n"); + fatconfig32.fc_rsvdseccount = 2; + } + else + { + fatconfig32.fc_rsvdseccount = fmt->ff_rsvdseccount; + } + } + else + { + fatconfig12.fc_rsvdseccount = 1; + fatconfig16.fc_rsvdseccount = 1; + fatconfig32.fc_rsvdseccount = 32; + } + /* Determine the number of sectors needed by the root directory. * This is a constant value, independent of cluster size for FAT12/16 */ @@ -592,10 +673,13 @@ mkfatfs_clustersearch(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var) if (var->fv_fattype != 32) { /* Calculate the number of sectors reqired to contain the selected - * number of root directory entries. + * number of root directory entries. This value is save in the var + * structure but will be overwritten if FAT32 is selected. FAT32 uses + * a cluster chain for the root directory, so the concept of the number + * of root directory entries does not apply to FAT32 */ - nrootdirsects = + var->fv_nrootdirsects = ((fmt->ff_rootdirentries << DIR_SHIFT) + var->fv_sectorsize - 1) >> var->fv_sectshift; /* The number of data sectors available (includes the fat itself) @@ -605,7 +689,7 @@ mkfatfs_clustersearch(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var) fatconfig12.fc_navailsects = fatconfig16.fc_navailsects = - var->fv_nsectors - nrootdirsects - fmt->ff_rsvdseccount; + fmt->ff_nsectors - var->fv_nrootdirsects - fatconfig12.fc_rsvdseccount; } /* Select an initial and terminal clustersize to use in the search (if these @@ -620,9 +704,6 @@ mkfatfs_clustersearch(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var) /* Check if FAT12 has not been excluded */ - fatconfig12.fc_nfatsects = 0; - fatconfig12.fc_nclusters = 0; -\ if (var->fv_fattype == 0 || var->fv_fattype == 12) { /* Try to configure a FAT12 filesystem with this cluster size */ @@ -639,9 +720,6 @@ mkfatfs_clustersearch(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var) /* Check if FAT16 has not been excluded */ - fatconfig16.fc_nfatsects = 0; - fatconfig16.fc_nclusters = 0; - if (var->fv_fattype == 0 || var->fv_fattype == 16) { /* Try to configure a FAT16 filesystem with this cluster size */ @@ -656,10 +734,33 @@ mkfatfs_clustersearch(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var) } } - /* Check if FAT32 has not been excluded */ + /* If either FAT12 or 16 was configured at this sector/cluster setting, + * then finish the configuration and break out now + */ - fatconfig32.fc_nfatsects = 0; - fatconfig32.fc_nclusters = 0; + if (fatconfig12.fc_nclusters || fatconfig16.fc_nclusters) + { + if ((!var->fv_fattype && fatconfig16.fc_nclusters > fatconfig12.fc_nclusters) || + (var ->fv_fattype == 16)) + { + /* The caller has selected FAT16 -OR- no FAT type has been selected, but + * the FAT16 selection has more clusters. Select FAT16. + */ + + mkfatfs_selectfat(16, fmt, var, &fatconfig16); + } + else + { + /* The caller has selected FAT12 -OR- no FAT type has been selected, but + * the FAT12 selected has more clusters. Selected FAT12 + */ + + mkfatfs_selectfat(12, fmt, var, &fatconfig12); + } + return OK; + } + + /* Check if FAT32 has not been excluded */ if (var->fv_fattype == 0 || var->fv_fattype == 32) { @@ -668,7 +769,7 @@ mkfatfs_clustersearch(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var) * because the size of the root directory cluster changes with cluster size. */ - fatconfig32.fc_navailsects = var->fv_nsectors - (1 << fmt->ff_clustshift) - fmt->ff_rsvdseccount; + fatconfig32.fc_navailsects = fmt->ff_nsectors - (1 << fmt->ff_clustshift) - fatconfig32.fc_rsvdseccount; /* Try to configure a FAT32 filesystem with this cluster size */ @@ -680,57 +781,13 @@ mkfatfs_clustersearch(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var) fatconfig32.fc_nclusters = 0; } } - } - - /* If any FAT was configured at this sector/cluster setting, then break out now */ - - if (fatconfig12.fc_nclusters || fatconfig16.fc_nclusters) - { - /* If both FAT12 and FAT16 ar possible, select the one with the largest - * number of clusters (unless one has already been selected) - */ - - if (!var->fv_fattype) - { - if (fatconfig16.fc_nclusters > fatconfig12.fc_nclusters) - { - var->fv_fattype = 16; - } - else - { - var->fv_fattype = 12; - } - } - fdbg("Selected FAT%d\n", var->fv_fattype); - - /* Then return the appropriate inforamation about the selected - * file system. - */ - - if (var->fv_fattype == 12) - { - var->fv_nclusters = fatconfig12.fc_nclusters; - var->fv_nfatsects = fatconfig12.fc_nfatsects; - } else { - var->fv_nclusters = fatconfig16.fc_nclusters; - var->fv_nfatsects = fatconfig16.fc_nfatsects; - } - var->fv_nrootdirsects = nrootdirsects; - return OK; - } - else if (fatconfig32.fc_nclusters) - { - /* Select FAT32 if we have not already done so */ + /* Select FAT32 if we have not already done so */ - var->fv_fattype = 32; - fdbg("Selected FAT%d\n", var->fv_fattype); - - var->fv_nclusters = fatconfig32.fc_nclusters; - var->fv_nfatsects = fatconfig32.fc_nfatsects; - var->fv_nrootdirsects = 1 << fmt->ff_clustshift; - return OK; + mkfatfs_selectfat(32, fmt, var, &fatconfig32); + return OK; + } } /* Otherwise, bump up the sectors/cluster for the next time around the loop. */ @@ -764,6 +821,122 @@ mkfatfs_clustersearch(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var) int mkfatfs_configfatfs(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var) { + int ret; + + /* Select the number of root directory entries (FAT12/16 only). If FAT32 is selected, + * this value will be cleared later + */ + + if (!fmt->ff_rootdirentries) + { + /* The caller did not specify the number of root directory entries; use a default of 512. */ + + fmt->ff_rootdirentries = 512; + } + + /* Search to determine the smallest (reasonable) cluster size. A by-product + * of this search will be the selection of the FAT size (12/16/32) if the + * caller has not specified the FAT size + */ + + ret = mkfatfs_clustersearch(fmt, var); + if (ret < 0) + { + fdbg("Failed to set cluster size\n"); + return ret; + } + + /* Perform FAT specific initialization */ + + /* Set up boot jump assuming FAT 12/16 offset to bootcode */ + + var->fv_jump[0] = OPCODE_JMP_REL8; + var->fv_jump[2] = OPCODE_NOP; + var->fv_bootcode = g_bootcodeblob; + var->fv_bootcodesize = sizeof(g_bootcodeblob); + + if (var->fv_fattype != 32) + { + /* Set up additional, non-zero FAT12/16 fields */ + + /* Patch in the correct offset to the boot code */ + + var->fv_jump[1] = BS16_BOOTCODE - 2; + g_bootcodeblob[3] = BS16_BOOTCODE + BOOTCODE_MSGOFFSET; + } + else + { + /* Patch in the correct offset to the boot code */ + + var->fv_jump[1] = BS32_BOOTCODE - 2; + g_bootcodeblob[3] = BS32_BOOTCODE + BOOTCODE_MSGOFFSET; + + /* The root directory is a cluster chain... its is initialize size is one cluster */ + + var->fv_nrootdirsects = 1 << fmt->ff_clustshift; + + /* The number of reported root directory entries should should be zero for + * FAT32 because the root directory is a cluster chain. + */ + + fmt->ff_rootdirentries = 0; + + /* Verify the caller's backupboot selection */ + + if (fmt->ff_backupboot <= 1 || fmt->ff_backupboot >= fmt->ff_rsvdseccount) + { + fdbg("Invalid backup boot sector: %d\n", fmt->ff_backupboot) + fmt->ff_backupboot = 0; + } + + /* Check if the caller has selected a location for the backup boot record */ + + if (!fmt->ff_backupboot) + { + /* There must be reserved sectors in order to have a backup boot sector */ + + if (fmt->ff_rsvdseccount > 0 && fmt->ff_rsvdseccount >= 2) + { + /* Sector 0 is the MBR; 1... ff_rsvdseccount are reserved. Try the next + * the last reserved sector. + */ + + fmt->ff_backupboot = fmt->ff_rsvdseccount - 1; + if (fmt->ff_backupboot > 6) + { + /* Limit the location to within the first 7 */ + + fmt->ff_backupboot = 6; + } + } + } + } + + /* Report the selected fat type */ + + fmt->ff_fattype = var->fv_fattype; + + /* Describe the configured filesystem */ + +#ifdef CONFIG_DEBUG + fdbg("Sector size: %d bytes\n", var->fv_sectorsize); + fdbg("Number of sectors: %d sectors\n", fmt->ff_nsectors); + fdbg("FAT size: %d bits\n", var->fv_fattype); + fdbg("Number FATs: %d\n", fmt->ff_fats); + fdbg("Sectors per cluster: %d sectors\n", 1 << fmt->ff_clustshift); + fdbg("FS size: %d sectors\n", var->fv_nfatsects); + fdbg(" %d clusters\n", var->fv_nclusters); + if (var->fv_fattype != 32) + { + fdbg("Root directory slots: %d\n", fmt->ff_rootdirentries); + } + fdbg("Volume ID: %08x\n", fmt->ff_volumeid); + fdbg("Volume Label: \"%c%c%c%c%c%c%c%c%c%c%c\"\n", + fmt->ff_volumelabel[0], fmt->ff_volumelabel[1], fmt->ff_volumelabel[2], + fmt->ff_volumelabel[3], fmt->ff_volumelabel[4], fmt->ff_volumelabel[5], + fmt->ff_volumelabel[6], fmt->ff_volumelabel[7], fmt->ff_volumelabel[8], + fmt->ff_volumelabel[9], fmt->ff_volumelabel[10]); +#endif return OK; } diff --git a/nuttx/fs/fat/fs_mkfatfs.c b/nuttx/fs/fat/fs_mkfatfs.c new file mode 100644 index 000000000..9fd902b4b --- /dev/null +++ b/nuttx/fs/fat/fs_mkfatfs.c @@ -0,0 +1,311 @@ +/**************************************************************************** + * fs/fat/fs_writefat.c + * + * Copyright (C) 2008 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 +#include + +#include +#include +#include +#include + +#include +#include +#include + +#include "fs_internal.h" +#include "fs_fat32.h" +#include "fs_mkfatfs.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mkfatfs_getgeometry + * + * Description: + * Get the sector size and number of sectors of the underlying block + * device. + * + * Input: + * 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 + * + ****************************************************************************/ + +static inline int mkfatfs_getgeometry(FAR struct fat_format_s *fmt, + FAR struct fat_var_s *var) +{ + struct geometry geometry; + int ret; + + /* Get the device geometry */ + + ret = DEV_GEOMETRY(geometry); + if (ret < 0) + { + fdbg("geometry() returned %d\n", ret); + return ret; + } + + if (!geometry.geo_available || !geometry.geo_writeenabled) + { + fdbg("Media is not available\n", ret); + return -ENODEV; + } + + /* Check if the user provided maxblocks was provided and, if so, that is it less than + * the actual number of blocks on the device. + */ + + if (fmt->ff_nsectors != 0) + { + if (fmt->ff_nsectors > geometry.geo_nsectors) + { + fdbg("User maxblocks (%d) exceeds blocks on device (%d)\n", + mt->ff_maxblocks, geometry.geo_nsectors); + return -EINVAL; + } + } + else + { + /* Use the actual number of blocks on the device */ + + fmt->ff_nsectors = geometry.geo_nsectors; + } + + /* Verify that we can handle this sector size */ + + var->fv_sectorsize = geometry.geo_sectorsize; + switch (var->fv_sectorsize) + { + case 512: + var->fv_sectshift = 9; + break; + + case 1024: + var->fv_sectshift = 10; + break; + + case 2048: + var->fv_sectshift = 11; + break; + + case 4096: + var->fv_sectshift = 12; + break; + + default: + fdbg("Unsupported sector size: %d\n", var->fv_sectorsize); + return -EPERM; + } + return 0; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mkfatfs + * + * Description: + * Make a FAT file system image on the specified block device + * + * Inputs: + * pathname - the full path to a registered block driver + * fmt - Describes characteristics of the desired filesystem + * + * Return: + * Zero (OK) on success; -1 (ERROR) on failure with errno set appropriately: + * + * EINVAL - NULL block driver string, bad number of FATS in 'fmt', bad FAT + * 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 + * EACCES - block driver does not support wrie or geometry methods + * + * Assumptions: + * - The caller must assure that the block driver is not mounted and not in + * use when this function is called. The result of formatting a mounted + * device is indeterminate (but likely not good). + * + ****************************************************************************/ +int mkfatfs(FAR const char *pathname, FAR struct fat_format_s *fmt) +{ + struct fat_var_s var; + int ret; + + /* Initialize */ + + memset(&var, 0, sizeof(struct fat_var_s)); + + /* Get the filesystem creation time */ + + var.fv_createtime = fat_systime2fattime(); + + /* Verify format options (only when DEBUG enabled) */ + +#ifdef CONFIG_DEBUG + if (!pathname) + { + fdbg("No block driver path\n"); + ret = -EINVAL; + goto errout; + } + + if (fmt->ff_nfats < 1 || fmt->ff_nfats > 4) + { + fdbg("Invalid number of fats: %d\n", fmt->ff_fats); + ret = -EINVAL; + goto errout; + } + + if (fmt->ff_fattype != 0 && fmt->ff_fattype != 12 && + fmt->ff_fattype != 16 && fmt->ff_fattype != 32) + { + fdbg("Invalid FAT size: %d\n", fmt->ff_fattype); + ret = -EINVAL; + goto errout; + } + var.fv_fattype = fmt->ff_fattype; + + /* The valid range off ff_clustshift is {0,1,..7} corresponding to + * cluster sizes of {1,2,..128} sectors. The special value of 0xff + * means that we should autoselect the cluster sizel. + */ + + if (fmt->ff_clustshift > 7 && fmt->ff_clustshift != 0xff) + { + fdbg("Invalid cluster shift value: %d\n", fmt->ff_clustshift); + ret = -EINVAL; + goto errout; + } + + if (fmt->ff_rootdirentries != 0 && (fmt->ff_rootdirentries < 16 || fmt->ff_rootdirentries > 32767)) + { + fdbg("Invalid number of root dir entries: %d\n", fmt->ff_rootdirentries); + ret = -EINVAL; + goto errout; + } + + if (fmt->ff_rsvdseccount != 0 && (fmt->ff_rsvdseccount < 1 || fmt->ff_rsvdseccount > 32767)) + { + fdbg("Invalid number of reserved sectors: %d\n", fmt->ff_rsvdseccount); + ret = -EINVAL; + goto errout; + } +#endif + + /* Find the inode of the block driver indentified by 'source' */ + + ret = open_blockdriver(pathname, 0, &var.fv_inode); + if (ret < 0) + { + fdbg("Failed to open %s\n", pathname); + goto errout; + } + + /* Make sure that the inode supports the write and geometry methods at a minimum */ + + if (!var.fv_inode->u.i_bops->write || !var.fv_inode->u.i_bops->geometry) + { + fdbg("%s does not support write or geometry methods\n", pathname); + ret = -EACCES; + goto errout_with_driver; + } + + /* Determine the volume configuration based upon the input values and upon the + * reported device geometry. + */ + + ret = mkfatfs_getgeometry(fmt, &var); + if (ret < 0) + { + goto errout_with_driver; + } + + /* Configure the file system */ + + ret = mkfatfs_configfatfs(fmt, &var); + if (ret < 0) + { + goto errout_with_driver; + } + + /* Allocate a buffer that will be working sector memory */ + + var.fv_sect = (ubyte*)malloc(var.fv_sectorsize); + if (!var.fv_sect) + { + fdbg("Failed to allocate working buffers\n"); + goto errout_with_driver; + } + + /* Write the filesystem to media */ + + ret = mkfatfs_writefatfs(fmt, &var); + +errout_with_driver: + /* Close the driver */ + + (void)close_blockdriver(var.fv_inode); + +errout: + /* Release all allocated memory */ + + if (var.fv_sect) + { + free(var.fv_sect); + } + + /* Return any reported errors */ + + if (ret < 0) + { + errno = -ret; + return ERROR; + } + return OK; +} diff --git a/nuttx/fs/fat/fs_mkfatfs.h b/nuttx/fs/fat/fs_mkfatfs.h index 31ad7b8af..a7b64d2e9 100644 --- a/nuttx/fs/fat/fs_mkfatfs.h +++ b/nuttx/fs/fat/fs_mkfatfs.h @@ -103,7 +103,6 @@ struct fat_var_s 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_nclusters; /* Number of clusters */ ubyte *fv_sect; /* Allocated working sector buffer */ diff --git a/nuttx/fs/fat/fs_writefat.c b/nuttx/fs/fat/fs_writefat.c index e40394cad..ee5979ddd 100644 --- a/nuttx/fs/fat/fs_writefat.c +++ b/nuttx/fs/fat/fs_writefat.c @@ -105,13 +105,13 @@ static inline void mkfatfs_initmbr(FAR struct fat_format_s *fmt, /* 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) + if (fmt->ff_nsectors >= 65536) { - MBR_PUTTOTSEC32(var->fv_sect, var->fv_nsectors); + MBR_PUTTOTSEC32(var->fv_sect, fmt->ff_nsectors); } else { - MBR_PUTTOTSEC16(var->fv_sect, (uint16)var->fv_nsectors); + MBR_PUTTOTSEC16(var->fv_sect, (uint16)fmt->ff_nsectors); } /* 1@21: Media code: f0, f8, f9-fa, fc-ff */ -- cgit v1.2.3