summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog6
-rw-r--r--nuttx/fs/fat/Kconfig19
-rw-r--r--nuttx/fs/fat/fs_fat32.c7
-rw-r--r--nuttx/fs/fat/fs_fat32.h28
-rw-r--r--nuttx/fs/fat/fs_fat32util.c4
-rw-r--r--nuttx/include/nuttx/fs/fat.h30
6 files changed, 87 insertions, 7 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index f1780c323..f56e14c04 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -3309,4 +3309,10 @@
by Kate).
* arch/avr/src: Fixes from AVR32 build errors that have crept in
over the time; incorporated Kconfig for AVR3 (Richard Cochran).
+ * fs/fat and include/nuttx/fs/fat.h: The FAT file system allocates
+ memory for sector I/O buffers used to exchange data with the
+ configured block driver. In some contexts, the block driver may
+ require DMA-capable memory. If CONFIG_FAT_DMAMEMORY is defined,
+ then the FAT FS will use platform-provided DMA memory allocators
+ to allocate the block driver I/O buffers.
diff --git a/nuttx/fs/fat/Kconfig b/nuttx/fs/fat/Kconfig
index fed054b5b..1de613ce4 100644
--- a/nuttx/fs/fat/Kconfig
+++ b/nuttx/fs/fat/Kconfig
@@ -41,9 +41,26 @@ config FAT_MAXFNAME
config FS_FATTIME
bool "FAT timestamps"
default n
- ---help---
+ ---help---
Support FAT date and time. NOTE: There is not
much sense in supporting FAT date and time unless you have a
hardware RTC or other way to get the time and date.
+config FAT_DMAMEMORY
+ bool "DMA memory allocator"
+ default n
+ ---help---
+ The FAT file system allocates two I/O buffers for data transfer, each
+ are the size of one device sector. One of the buffers is allocated
+ once for each FAT volume that is mounted; the other buffers are
+ allocated each time a FAT file is opened.
+
+ Some hardware, however, may require special DMA-capable memory in
+ order to perform the the transfers. If FAT_DMAMEMORY is defined
+ then the architecture-specific hardware must provide the funtions
+ fat_dma_alloc() and fat_dma_free(): fat_dmalloc() will allocate
+ DMA-capable memory of the specified size; fat_dmafree() is the
+ corresponding function that will be called to free the DMA-capable
+ memory.
+
endif
diff --git a/nuttx/fs/fat/fs_fat32.c b/nuttx/fs/fat/fs_fat32.c
index 7b7ce1f5f..60622e2f7 100644
--- a/nuttx/fs/fat/fs_fat32.c
+++ b/nuttx/fs/fat/fs_fat32.c
@@ -302,7 +302,7 @@ static int fat_open(FAR struct file *filep, const char *relpath,
/* Create a file buffer to support partial sector accesses */
- ff->ff_buffer = (uint8_t*)kmalloc(fs->fs_hwsectorsize);
+ ff->ff_buffer = (uint8_t*)fat_io_alloc(fs->fs_hwsectorsize);
if (!ff->ff_buffer)
{
ret = -ENOMEM;
@@ -405,7 +405,7 @@ static int fat_close(FAR struct file *filep)
if (ff->ff_buffer)
{
- kfree(ff->ff_buffer);
+ fat_io_free(ff->ff_buffer);
}
/* Then free the file structure itself. */
@@ -1651,8 +1651,9 @@ static int fat_unbind(void *handle, FAR struct inode **blkdriver)
if (fs->fs_buffer)
{
- kfree(fs->fs_buffer);
+ fat_io_free(fs->fs_buffer);
}
+
kfree(fs);
}
diff --git a/nuttx/fs/fat/fs_fat32.h b/nuttx/fs/fat/fs_fat32.h
index 5b82ff701..c7fa5219c 100644
--- a/nuttx/fs/fat/fs_fat32.h
+++ b/nuttx/fs/fat/fs_fat32.h
@@ -48,6 +48,7 @@
#include <semaphore.h>
#include <time.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/fs/dirent.h>
/****************************************************************************
@@ -677,6 +678,33 @@
#endif
/****************************************************************************
+ * Name: fat_io_alloc and fat_io_free
+ *
+ * Description:
+ * The FAT file system allocates two I/O buffers for data transfer, each
+ * are the size of one device sector. One of the buffers is allocated
+ * once for each FAT volume that is mounted; the other buffers are
+ * allocated each time a FAT file is opened.
+ *
+ * Some hardware, however, may require special DMA-capable memory in
+ * order to perform the the transfers. If CONFIG_FAT_DMAMEMORY is defined
+ * then the architecture-specific hardware must provide the funtions
+ * fat_dma_alloc() and fat_dma_free() as prototyped below: fat_dmalloc()
+ * will allocate DMA-capable memory of the specified size; fat_dmafree()
+ * is the corresponding function that will be called to free the DMA-
+ * capable memory.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_FAT_DMAMEMORY
+# define fat_io_alloc(s) fat_dma_alloc(s)
+# define fat_io_free(s) fat_dma_free(s)
+#else
+# define fat_io_alloc(s) kmalloc(s)
+# define fat_io_free(s) kfree(s)
+#endif
+
+/****************************************************************************
* Public Types
****************************************************************************/
diff --git a/nuttx/fs/fat/fs_fat32util.c b/nuttx/fs/fat/fs_fat32util.c
index b88046d79..f8f5ef495 100644
--- a/nuttx/fs/fat/fs_fat32util.c
+++ b/nuttx/fs/fat/fs_fat32util.c
@@ -542,7 +542,7 @@ int fat_mount(struct fat_mountpt_s *fs, bool writeable)
/* Allocate a buffer to hold one hardware sector */
- fs->fs_buffer = (uint8_t*)kmalloc(fs->fs_hwsectorsize);
+ fs->fs_buffer = (uint8_t*)fat_io_alloc(fs->fs_hwsectorsize);
if (!fs->fs_buffer)
{
ret = -ENOMEM;
@@ -668,7 +668,7 @@ int fat_mount(struct fat_mountpt_s *fs, bool writeable)
return OK;
errout_with_buffer:
- kfree(fs->fs_buffer);
+ fat_io_free(fs->fs_buffer);
fs->fs_buffer = 0;
errout:
fs->fs_mounted = false;
diff --git a/nuttx/include/nuttx/fs/fat.h b/nuttx/include/nuttx/fs/fat.h
index f69bd8571..3ae0fbee2 100644
--- a/nuttx/include/nuttx/fs/fat.h
+++ b/nuttx/include/nuttx/fs/fat.h
@@ -75,11 +75,39 @@ extern "C" {
#define EXTERN extern
#endif
-/* Non-standard functions to get and set FAT file/directory attributes */
+/****************************************************************************
+ * Name: fat_getattrib and fat_setattrib
+ *
+ * Description:
+ * Non-standard functions to get and set FAT file/directory attributes
+ *
+ ****************************************************************************/
EXTERN int fat_getattrib(const char *path, fat_attrib_t *attrib);
EXTERN int fat_setattrib(const char *path, fat_attrib_t setbits, fat_attrib_t clearbits);
+/****************************************************************************
+ * Name: fat_dma_alloc and fat_dma_free
+ *
+ * Description:
+ * The FAT file system allocates two I/O buffers for data transfer, each
+ * are the size of one device sector. One of the buffers is allocated
+ * once for each FAT volume that is mounted; the other buffers are
+ * allocated each time a FAT file is opened.
+ *
+ * Some hardware, however, may require special DMA-capable memory in
+ * order to perform the the transfers. If CONFIG_FAT_DMAMEMORY is defined
+ * then the architecture-specific hardware must provide the funtions
+ * fat_dma_alloc() and fat_dma_free() as prototyped below: fat_dmalloc()
+ * will allocate DMA-capable memory of the specified size; fat_dmafree()
+ * is the corresponding function that will be called to free the DMA-
+ * capable memory.
+ *
+ ****************************************************************************/
+
+EXTERN FAR void *fat_dma_alloc(size_t size);
+EXTERN void fat_dma_free(FAR void *memory);
+
#undef EXTERN
#ifdef __cplusplus
}