summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/drivers/Kconfig27
-rw-r--r--nuttx/drivers/Makefile11
-rw-r--r--nuttx/drivers/mmcsd/mmcsd_sdio.c25
-rw-r--r--nuttx/drivers/mtd/Kconfig39
-rw-r--r--nuttx/drivers/mtd/Make.defs8
-rw-r--r--nuttx/drivers/mtd/ftl.c22
-rw-r--r--nuttx/drivers/mtd/mtd_procfs.c3
-rw-r--r--nuttx/drivers/mtd/mtd_rwbuffer.c417
-rw-r--r--nuttx/drivers/mtd/smart.c3
-rw-r--r--nuttx/drivers/rwbuffer.c601
-rwxr-xr-x[-rw-r--r--]nuttx/include/nuttx/rwbuffer.h82
11 files changed, 1028 insertions, 210 deletions
diff --git a/nuttx/drivers/Kconfig b/nuttx/drivers/Kconfig
index 5277873da..6828c829f 100644
--- a/nuttx/drivers/Kconfig
+++ b/nuttx/drivers/Kconfig
@@ -35,6 +35,33 @@ config LOOP
file (or character device) as a block device. See losetup() and
loteardown() in include/nuttx/fs/fs.h.
+config DRVR_WRITEBUFFER
+ bool "Enable write buffer support"
+ default n
+ ---help---
+ Enable generic write buffering support that can be used by a variety
+ of drivers.
+
+if DRVR_WRITEBUFFER
+
+config DRVR_WRDELAY
+ int "Write flush delay"
+ default 350
+ ---help---
+ If there is no write activity for this configured amount of time,
+ then the contents will be automatically flushed to the media. This
+ reduces the likelihood that data will be stuck in the write buffer
+ at the time of power down.
+
+endif # DRVR_WRITEBUFFER
+
+config DRVR_READAHEAD
+ bool "Enable read-ahead buffer support"
+ default n
+ ---help---
+ Enable generic read-ahead buffering support that can be used by a
+ variety of drivers.
+
config RAMDISK
bool "RAM Disk Support"
default n
diff --git a/nuttx/drivers/Makefile b/nuttx/drivers/Makefile
index e4576ac57..0ea6e2f8f 100644
--- a/nuttx/drivers/Makefile
+++ b/nuttx/drivers/Makefile
@@ -1,7 +1,7 @@
############################################################################
# drivers/Makefile
#
-# Copyright (C) 2007-2013 Gregory Nutt. All rights reserved.
+# Copyright (C) 2007-2014 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
@@ -73,7 +73,14 @@ ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
CSRCS += dev_null.c dev_zero.c loop.c
ifneq ($(CONFIG_DISABLE_MOUNTPOINT),y)
- CSRCS += ramdisk.c rwbuffer.c
+ CSRCS += ramdisk.c
+ifneq ($(CONFIG_DRVR_WRITEBUFFER),y)
+ CSRCS += rwbuffer.c
+else
+ifneq ($(CONFIG_DRVR_READAHEAD),y)
+ CSRCS += rwbuffer.c
+endif
+endif
endif
ifeq ($(CONFIG_CAN),y)
diff --git a/nuttx/drivers/mmcsd/mmcsd_sdio.c b/nuttx/drivers/mmcsd/mmcsd_sdio.c
index b6838706a..62e293e5a 100644
--- a/nuttx/drivers/mmcsd/mmcsd_sdio.c
+++ b/nuttx/drivers/mmcsd/mmcsd_sdio.c
@@ -144,7 +144,7 @@ struct mmcsd_state_s
#endif
/* Read-ahead and write buffering support */
-#if defined(CONFIG_FS_WRITEBUFFER) || defined(CONFIG_FS_READAHEAD)
+#if defined(CONFIG_DRVR_WRITEBUFFER) || defined(CONFIG_DRVR_READAHEAD)
struct rwbuffer_s rwbuffer;
#endif
};
@@ -203,7 +203,7 @@ static ssize_t mmcsd_readsingle(FAR struct mmcsd_state_s *priv,
static ssize_t mmcsd_readmultiple(FAR struct mmcsd_state_s *priv,
FAR uint8_t *buffer, off_t startblock, size_t nblocks);
#endif
-#ifdef CONFIG_FS_READAHEAD
+#ifdef CONFIG_DRVR_READAHEAD
static ssize_t mmcsd_reload(FAR void *dev, FAR uint8_t *buffer,
off_t startblock, size_t nblocks);
#endif
@@ -214,7 +214,7 @@ static ssize_t mmcsd_writesingle(FAR struct mmcsd_state_s *priv,
static ssize_t mmcsd_writemultiple(FAR struct mmcsd_state_s *priv,
FAR const uint8_t *buffer, off_t startblock, size_t nblocks);
#endif
-#ifdef CONFIG_FS_WRITEBUFFER
+#ifdef CONFIG_DRVR_WRITEBUFFER
static ssize_t mmcsd_flush(FAR void *dev, FAR const uint8_t *buffer,
off_t startblock, size_t nblocks);
#endif
@@ -1538,7 +1538,7 @@ static ssize_t mmcsd_readmultiple(FAR struct mmcsd_state_s *priv,
*
****************************************************************************/
-#ifdef CONFIG_FS_READAHEAD
+#ifdef CONFIG_DRVR_READAHEAD
static ssize_t mmcsd_reload(FAR void *dev, FAR uint8_t *buffer,
off_t startblock, size_t nblocks)
{
@@ -1911,12 +1911,12 @@ static ssize_t mmcsd_writemultiple(FAR struct mmcsd_state_s *priv,
*
****************************************************************************/
-#if defined(CONFIG_FS_WRITABLE) && defined(CONFIG_FS_WRITEBUFFER)
+#if defined(CONFIG_FS_WRITABLE) && defined(CONFIG_DRVR_WRITEBUFFER)
static ssize_t mmcsd_flush(FAR void *dev, FAR const uint8_t *buffer,
off_t startblock, size_t nblocks)
{
FAR struct mmcsd_state_s *priv = (FAR struct mmcsd_state_s *)dev;
-#ifndef CONFIG_MMCSD_MULTIBLOCK_DISABLE
+#ifdef CONFIG_MMCSD_MULTIBLOCK_DISABLE
size_t block;
size_t endblock;
#endif
@@ -2028,7 +2028,7 @@ static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer,
size_t startsector, unsigned int nsectors)
{
FAR struct mmcsd_state_s *priv;
-#if !defined(CONFIG_FS_READAHEAD) && defined(CONFIG_MMCSD_MULTIBLOCK_DISABLE)
+#if !defined(CONFIG_DRVR_READAHEAD) && defined(CONFIG_MMCSD_MULTIBLOCK_DISABLE)
size_t sector;
size_t endsector;
#endif
@@ -2043,7 +2043,7 @@ static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer,
{
mmcsd_takesem(priv);
-#if defined(CONFIG_FS_READAHEAD)
+#if defined(CONFIG_DRVR_READAHEAD)
/* Get the data from the read-ahead buffer */
ret = rwb_read(&priv->rwbuffer, startsector, nsectors, buffer);
@@ -2103,7 +2103,7 @@ static ssize_t mmcsd_write(FAR struct inode *inode, FAR const unsigned char *buf
size_t startsector, unsigned int nsectors)
{
FAR struct mmcsd_state_s *priv;
-#if !defined(CONFIG_FS_WRITEBUFFER) && defined(CONFIG_MMCSD_MULTIBLOCK_DISABLE)
+#if defined(CONFIG_MMCSD_MULTIBLOCK_DISABLE)
size_t sector;
size_t endsector;
#endif
@@ -2115,7 +2115,7 @@ static ssize_t mmcsd_write(FAR struct inode *inode, FAR const unsigned char *buf
mmcsd_takesem(priv);
-#if defined(CONFIG_FS_WRITEBUFFER)
+#if defined(CONFIG_DRVR_WRITEBUFFER)
/* Write the data to the write buffer */
ret = rwb_write(&priv->rwbuffer, startsector, nsectors, buffer);
@@ -3271,9 +3271,10 @@ int mmcsd_slotinitialize(int minor, FAR struct sdio_dev_s *dev)
}
}
-#if defined(CONFIG_FS_WRITEBUFFER) || defined(CONFIG_FS_READAHEAD)
+#if defined(CONFIG_DRVR_WRITEBUFFER) || defined(CONFIG_DRVR_READAHEAD)
/* Initialize buffering */
+#warning "Missing setup of rwbuffer"
ret = rwb_initialize(&priv->rwbuffer);
if (ret < 0)
{
@@ -3298,7 +3299,7 @@ int mmcsd_slotinitialize(int minor, FAR struct sdio_dev_s *dev)
return OK;
errout_with_buffers:
-#if defined(CONFIG_FS_WRITEBUFFER) || defined(CONFIG_FS_READAHEAD)
+#if defined(CONFIG_DRVR_WRITEBUFFER) || defined(CONFIG_DRVR_READAHEAD)
rwb_uninitialize(&priv->rwbuffer);
errout_with_hwinit:
#endif
diff --git a/nuttx/drivers/mtd/Kconfig b/nuttx/drivers/mtd/Kconfig
index 1d56a8960..26945d5c6 100644
--- a/nuttx/drivers/mtd/Kconfig
+++ b/nuttx/drivers/mtd/Kconfig
@@ -66,6 +66,40 @@ config MTD_BYTE_WRITE
support such writes. The SMART file system can take advantage of
this option if it is enabled.
+config MTD_WRBUFFER
+ bool "Enable MTD write buffering
+ default n
+ depends on DRVR_WRITEBUFFER
+ ---help---
+ Build the mtd_rwbuffer layer and enable support for write buffering.
+
+if MTD_WRBUFFER
+
+config MTD_NWRBLOCKS
+ int "MTD write buffer size"
+ default 4
+ ---help---
+ The size of the MTD write buffer (in blocks)
+
+endif # MTD_WRBUFFER
+
+config MTD_READAHEAD
+ bool "Enable MTD read-ahead buffering
+ default n
+ depends on DRVR_READAHEAD
+ ---help---
+ Build the mtd_rwbuffer layer and enable support for read-ahead buffering.
+
+if MTD_READAHEAD
+
+config MTD_NRDBLOCKS
+ int "MTD read-head buffer size"
+ default 4
+ ---help---
+ The size of the MTD read-ahead buffer (in blocks)
+
+endif # MTD_READAHEAD
+
config MTD_CONFIG
bool "Enable Dev Config (MTD based) device"
default n
@@ -73,6 +107,8 @@ config MTD_CONFIG
Provides a /dev/config device for saving / restoring application
configuration data to a standard MTD device or partition.
+if MTD_CONFIG
+
config MTD_CONFIG_RAM_CONSOLIDATE
bool "Always use RAM consolidation method (work in progress)"
default n
@@ -97,13 +133,14 @@ config MTD_CONFIG_RAM_CONSOLIDATE
config MTD_CONFIG_ERASEDVALUE
hex "Erased value of bytes on the MTD device"
- depends on MTD_CONFIG
default 0xff
---help---
Specifies the value of the erased state of the MTD FLASH. For
most FLASH parts, this is 0xff, but could also be zero depending
on the device.
+endif # MTD_CONFIG
+
comment "MTD Device Drivers"
menuconfig MTD_NAND
diff --git a/nuttx/drivers/mtd/Make.defs b/nuttx/drivers/mtd/Make.defs
index c7d8ea18d..ff1b899d9 100644
--- a/nuttx/drivers/mtd/Make.defs
+++ b/nuttx/drivers/mtd/Make.defs
@@ -49,6 +49,14 @@ ifeq ($(CONFIG_MTD_SECT512),y)
CSRCS += sector512.c
endif
+ifeq ($(CONFIG_MTD_WRBUFFER),y)
+CSRCS += mtd_rwbuffer.c
+else
+ifeq ($(CONFIG_MTD_READAHEAD),y)
+CSRCS += mtd_rwbuffer.c
+endif
+endif
+
ifeq ($(CONFIG_MTD_NAND),y)
CSRCS += mtd_nand.c mtd_onfi.c mtd_nandscheme.c mtd_nandmodel.c mtd_modeltab.c
ifeq ($(CONFIG_MTD_NAND_SWECC),y)
diff --git a/nuttx/drivers/mtd/ftl.c b/nuttx/drivers/mtd/ftl.c
index 364da3695..f2fb3b6d1 100644
--- a/nuttx/drivers/mtd/ftl.c
+++ b/nuttx/drivers/mtd/ftl.c
@@ -56,11 +56,11 @@
#include <nuttx/rwbuffer.h>
/****************************************************************************
- * Private Definitions
+ * Pre-processor Definitions
****************************************************************************/
-#if defined(CONFIG_FS_READAHEAD) || (defined(CONFIG_FS_WRITABLE) && defined(CONFIG_FS_WRITEBUFFER))
-# defined CONFIG_FTL_RWBUFFER 1
+#if defined(CONFIG_DRVR_READAHEAD) || defined(CONFIG_DRVR_WRITEBUFFER)
+# define CONFIG_FTL_RWBUFFER 1
#endif
/****************************************************************************
@@ -111,7 +111,7 @@ static const struct block_operations g_bops =
#ifdef CONFIG_FS_WRITABLE
ftl_write, /* write */
#else
- NULL, /* write */
+ NULL, /* write */
#endif
ftl_geometry, /* geometry */
ftl_ioctl /* ioctl */
@@ -181,13 +181,14 @@ static ssize_t ftl_reload(FAR void *priv, FAR uint8_t *buffer,
static ssize_t ftl_read(FAR struct inode *inode, unsigned char *buffer,
size_t start_sector, unsigned int nsectors)
{
- struct ftl_struct_s *dev;
+ FAR struct ftl_struct_s *dev;
fvdbg("sector: %d nsectors: %d\n", start_sector, nsectors);
DEBUGASSERT(inode && inode->i_private);
- dev = (struct ftl_struct_s *)inode->i_private;
-#ifdef CONFIG_FS_READAHEAD
+
+ dev = (FAR struct ftl_struct_s *)inode->i_private;
+#ifdef CONFIG_DRVR_READAHEAD
return rwb_read(&dev->rwb, start_sector, nsectors, buffer);
#else
return ftl_reload(dev, buffer, start_sector, nsectors);
@@ -388,7 +389,7 @@ static ssize_t ftl_write(FAR struct inode *inode, const unsigned char *buffer,
DEBUGASSERT(inode && inode->i_private);
dev = (struct ftl_struct_s *)inode->i_private;
-#ifdef CONFIG_FS_WRITEBUFFER
+#ifdef CONFIG_DRVR_WRITEBUFFER
return rwb_write(&dev->rwb, start_sector, nsectors, buffer);
#else
return ftl_flush(dev, buffer, start_sector, nsectors);
@@ -566,15 +567,16 @@ int ftl_initialize(int minor, FAR struct mtd_dev_s *mtd)
dev->rwb.nblocks = dev->geo.neraseblocks * dev->blkper;
dev->rwb.dev = (FAR void *)dev;
-#if defined(CONFIG_FS_WRITABLE) && defined(CONFIG_FS_WRITEBUFFER)
+#if defined(CONFIG_FS_WRITABLE) && defined(CONFIG_DRVR_WRITEBUFFER)
dev->rwb.wrmaxblocks = dev->blkper;
dev->rwb.wrflush = ftl_flush;
#endif
-#ifdef CONFIG_FS_READAHEAD
+#ifdef CONFIG_DRVR_READAHEAD
dev->rwb.rhmaxblocks = dev->blkper;
dev->rwb.rhreload = ftl_reload;
#endif
+
ret = rwb_initialize(&dev->rwb);
if (ret < 0)
{
diff --git a/nuttx/drivers/mtd/mtd_procfs.c b/nuttx/drivers/mtd/mtd_procfs.c
index 26f2880b8..54366789b 100644
--- a/nuttx/drivers/mtd/mtd_procfs.c
+++ b/nuttx/drivers/mtd/mtd_procfs.c
@@ -327,6 +327,7 @@ static int mtd_stat(const char *relpath, struct stat *buf)
* in the procfs system simply for information purposes (if desired).
*
****************************************************************************/
+
int mtd_register(FAR struct mtd_dev_s *mtd, FAR const char *name)
{
FAR struct mtd_dev_s *plast;
@@ -359,6 +360,8 @@ int mtd_register(FAR struct mtd_dev_s *mtd, FAR const char *name)
plast->pnext = mtd;
}
+
+ return OK;
}
#endif /* !CONFIG_DISABLE_MOUNTPOINT && CONFIG_FS_PROCFS */
diff --git a/nuttx/drivers/mtd/mtd_rwbuffer.c b/nuttx/drivers/mtd/mtd_rwbuffer.c
new file mode 100644
index 000000000..3aed371af
--- /dev/null
+++ b/nuttx/drivers/mtd/mtd_rwbuffer.c
@@ -0,0 +1,417 @@
+/************************************************************************************
+ * drivers/mtd/mtd_rwbuffer.c
+ * MTD driver that contains another MTD driver and provides read-ahead and/or write
+ * buffering.
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 <stdint.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <string.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/rwbuffer.h>
+#include <nuttx/fs/ioctl.h>
+#include <nuttx/mtd/mtd.h>
+
+#if defined(CONFIG_DRVR_WRITEBUFFER) || defined(CONFIG_DRVR_READAHEAD)
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+#ifndef CONFIG_MTD_NWRBLOCKS
+# define CONFIG_MTD_NWRBLOCKS 4
+#endif
+
+#ifndef CONFIG_MTD_NRDBLOCKS
+# define CONFIG_MTD_NRDBLOCKS 4
+#endif
+
+/************************************************************************************
+ * Private Types
+ ************************************************************************************/
+
+/* This type represents the state of the MTD device. The struct mtd_dev_s must
+ * appear at the beginning of the definition so that you can freely cast between
+ * pointers to struct mtd_dev_s and struct mtd_rwbuffer_s.
+ */
+
+struct mtd_rwbuffer_s
+{
+ struct mtd_dev_s mtd; /* Our exported MTD interface */
+ FAR struct mtd_dev_s *dev; /* Saved lower level MTD interface instance */
+ struct rwbuffer_s rwb; /* The rwbuffer state structure */
+ uint16_t spb; /* Number of sectors per block */
+};
+
+/************************************************************************************
+ * Private Function Prototypes
+ ************************************************************************************/
+
+/* rwbuffer callouts */
+
+static ssize_t mtd_reload(FAR void *dev, FAR uint8_t *buffer, off_t startblock,
+ size_t nblocks);
+static ssize_t mtd_flush(FAR void *dev, FAR const uint8_t *buffer, off_t startblock,
+ size_t nblocks);
+
+/* MTD driver methods */
+
+static int mtd_erase(FAR struct mtd_dev_s *dev, off_t block, size_t nsectors);
+static ssize_t mtd_bread(FAR struct mtd_dev_s *dev, off_t block,
+ size_t nsectors, FAR uint8_t *buf);
+static ssize_t mtd_bwrite(FAR struct mtd_dev_s *dev, off_t block,
+ size_t nsectors, FAR const uint8_t *buf);
+static ssize_t mtd_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
+ FAR uint8_t *buffer);
+static int mtd_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg);
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: mtd_reload
+ *
+ * Description:
+ * Reload the read-ahead buffer
+ *
+ ************************************************************************************/
+
+static ssize_t mtd_reload(FAR void *dev, FAR uint8_t *buffer, off_t startblock,
+ size_t nblocks)
+{
+ FAR struct mtd_rwbuffer_s *priv = (FAR struct mtd_rwbuffer_s *)dev;
+ DEBUGASSERT(priv && priv->dev);
+
+ /* This is just a pass-through to the contained MTD */
+
+ return priv->dev->bread(priv->dev, startblock, nblocks, buffer);
+}
+
+/************************************************************************************
+ * Name: mtd_flush
+ *
+ * Description:
+ * Flush the write buffer to hardware
+ *
+ ************************************************************************************/
+
+static ssize_t mtd_flush(FAR void *dev, FAR const uint8_t *buffer, off_t startblock,
+ size_t nblocks)
+{
+ FAR struct mtd_rwbuffer_s *priv = (FAR struct mtd_rwbuffer_s *)dev;
+ DEBUGASSERT(priv && priv->dev);
+
+ /* This is just a pass-through to the contained MTD */
+
+ return priv->dev->bwrite(priv->dev, startblock, nblocks, buffer);
+}
+
+/************************************************************************************
+ * Name: mtd_erase
+ ************************************************************************************/
+
+static int mtd_erase(FAR struct mtd_dev_s *dev, off_t block, size_t nblocks)
+{
+ FAR struct mtd_rwbuffer_s *priv = (FAR struct mtd_rwbuffer_s *)dev;
+ off_t sector;
+ size_t nsectors;
+ int ret;
+
+ fvdbg("block: %08lx nsectors: %lu\n",
+ (unsigned long)block, (unsigned int)nsectors);
+
+ /* Convert to logical sectors and sector numbers */
+
+ sector = block * priv->spb;
+ nsectors = nblocks * priv->spb;
+
+ /* Then invalidate in cached data */
+
+ ret = rwb_invalidate(&priv->rwb, sector, nsectors);
+ if (ret < 0)
+ {
+ fdbg("ERROR: rwb_invalidate failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Then let the lower level MTD driver do the real erase */
+
+ return priv->dev->erase(priv->dev, block, nblocks);
+}
+
+/************************************************************************************
+ * Name: mtd_bread
+ ************************************************************************************/
+
+static ssize_t mtd_bread(FAR struct mtd_dev_s *dev, off_t sector,
+ size_t nsectors, FAR uint8_t *buffer)
+{
+ FAR struct mtd_rwbuffer_s *priv = (FAR struct mtd_rwbuffer_s *)dev;
+
+ /* Let the rwbuffer logic do it real work. It will call out to mtd_reload if is
+ * needs to read any data.
+ */
+
+ return rwb_read(&priv->rwb, sector, nsectors, buffer);
+}
+
+/************************************************************************************
+ * Name: mtd_bwrite
+ ************************************************************************************/
+
+static ssize_t mtd_bwrite(FAR struct mtd_dev_s *dev, off_t block, size_t nsectors,
+ FAR const uint8_t *buffer)
+{
+ FAR struct mtd_rwbuffer_s *priv = (FAR struct mtd_rwbuffer_s *)dev;
+
+ /* Let the rwbuffer logic do it real work. It will call out to wrb_reload it is
+ * needs to read any data.
+ */
+
+ return rwb_write(&priv->rwb, block, nsectors, buffer);
+}
+
+/************************************************************************************
+ * Name: mtd_read
+ ************************************************************************************/
+
+static ssize_t mtd_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
+ FAR uint8_t *buffer)
+{
+ FAR struct mtd_rwbuffer_s *priv = (FAR struct mtd_rwbuffer_s *)dev;
+
+ /* Let the rwbuffer logic do it real work. It will call out to mtd_reload it is
+ * needs to read any data.
+ */
+
+ return mtd_readbytes(&priv->rwb, offset, nbytes, buffer);
+}
+
+/************************************************************************************
+ * Name: mtd_ioctl
+ ************************************************************************************/
+
+static int mtd_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
+{
+ FAR struct mtd_rwbuffer_s *priv = (FAR struct mtd_rwbuffer_s *)dev;
+ int ret = -EINVAL; /* Assume good command with bad parameters */
+
+ fvdbg("cmd: %d \n", cmd);
+
+ switch (cmd)
+ {
+ case MTDIOC_GEOMETRY:
+ {
+ FAR struct mtd_geometry_s *geo = (FAR struct mtd_geometry_s *)((uintptr_t)arg);
+ if (geo)
+ {
+ /* Populate the geometry structure with information need to know
+ * the capacity and how to access the device.
+ *
+ * NOTE: that the device is treated as though it where just an array
+ * of fixed size blocks. That is most likely not true, but the client
+ * will expect the device logic to do whatever is necessary to make it
+ * appear so.
+ */
+
+ geo->blocksize = priv->rwb.blocksize;
+ geo->erasesize = priv->rwb.blocksize* priv->spb;
+ geo->neraseblocks = priv->rwb.nblocks * priv->spb;
+ ret = OK;
+
+ fvdbg("blocksize: %d erasesize: %d neraseblocks: %d\n",
+ geo->blocksize, geo->erasesize, geo->neraseblocks);
+ }
+ }
+ break;
+
+ case MTDIOC_BULKERASE:
+ {
+ /* Erase the entire device */
+
+ ret = priv->dev->ioctl(priv->dev, MTDIOC_BULKERASE, 0);
+ if (ret >= 0)
+ {
+ fdbg("ERROR: Device ioctl failed: %d\n", ret);
+ break;
+ }
+
+ /* Then invalidate in cached data */
+
+ ret = rwb_invalidate(&priv->rwb,0, priv->rwb.nblocks);
+ if (ret < 0)
+ {
+ fdbg("ERROR: rwb_invalidate failed: %d\n", ret);
+ }
+ }
+ break;
+
+ case MTDIOC_XIPBASE:
+ default:
+ ret = -ENOTTY; /* Bad command */
+ break;
+ }
+
+ fvdbg("return %d\n", ret);
+ return ret;
+}
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: mtd_rwb_initialize
+ *
+ * Description:
+ * Create an initialized MTD device instance. This MTD driver contains another
+ * MTD driver and converts a larger sector size to a standard 512 byte sector
+ * size.
+ *
+ * MTD devices are not registered in the file system, but are created as instances
+ * that can be bound to other functions (such as a block or character driver front
+ * end).
+ *
+ ************************************************************************************/
+
+FAR struct mtd_dev_s *mtd_rwb_initialize(FAR struct mtd_dev_s *mtd)
+{
+ FAR struct mtd_rwbuffer_s *priv;
+ struct mtd_geometry_s geo;
+ int ret;
+
+ fvdbg("mtd: %p\n", mtd);
+ DEBUGASSERT(mtd && mtd->ioctl);
+
+ /* Get the device geometry */
+
+ ret = mtd->ioctl(mtd, MTDIOC_GEOMETRY, (unsigned long)((uintptr_t)&geo));
+ if (ret < 0)
+ {
+ fdbg("ERROR: MTDIOC_GEOMETRY ioctl failed: %d\n", ret);
+ return NULL;
+ }
+
+ /* Allocate a state structure (we allocate the structure instead of using
+ * a fixed, static allocation so that we can handle multiple FLASH devices.
+ * The current implementation would handle only one FLASH part per SPI
+ * device (only because of the SPIDEV_FLASH definition) and so would have
+ * to be extended to handle multiple FLASH parts on the same SPI bus.
+ */
+
+ priv = (FAR struct mtd_rwbuffer_s *)kzalloc(sizeof(struct mtd_rwbuffer_s));
+ if (priv)
+ {
+ /* Initialize the allocated structure. (unsupported methods/fields
+ * were already nullified by kzalloc).
+ */
+
+ priv->mtd.erase = mtd_erase; /* Our MTD erase method */
+ priv->mtd.bread = mtd_bread; /* Our MTD bread method */
+ priv->mtd.bwrite = mtd_bwrite; /* Our MTD bwrite method */
+ priv->mtd.read = mtd_read; /* Our MTD read method */
+ priv->mtd.ioctl = mtd_ioctl; /* Our MTD ioctl method */
+
+ priv->dev = mtd; /* The contained MTD instance */
+
+ /* Sectors per block. The erase block size must be an even multiple
+ * of the sector size.
+ */
+
+ priv->spb = geo.erasesize / geo.blocksize;
+ DEBUGASSERT((size_t)priv->spb * geo_blocksize = geo.erasesize);
+
+ /* Values must be provided to rwb_initialize() */
+ /* Supported geometry */
+
+ priv->rwb.blocksize = geo.blocksize;
+ priv->rwb.nblocks = geo.neraseblocks * priv->spb;
+
+ /* Buffer setup */
+
+#ifdef CONFIG_DRVR_WRITEBUFFER
+ priv->rwb.wrmaxblocks = CONFIG_MTD_NWRBLOCKS;
+#endif
+#ifdef CONFIG_DRVR_READAHEAD
+ priv->rwb.rhmaxblocks = CONFIG_MTD_NRDBLOCKS;
+#endif
+
+ /* Callouts */
+
+ priv->rwb.dev = priv; /* Device state passed to callouts */
+ priv->rwb.wrflush = mtd_flush; /* Callout to flush buffer */
+ priv->rwb.rhreload = mtd_reload; /* Callout to reload buffer */
+
+ /* Initialize read-ahead/write buffering */
+
+ ret = rwb_initialize(&priv->rwb);
+ if (ret < 0)
+ {
+ fdbg("ERROR: rwb_initialize failed: %d\n", ret);
+ kfree(priv);
+ return NULL;
+ }
+ }
+
+ /* Register the MTD with the procfs system if enabled */
+
+#ifdef CONFIG_MTD_REGISTRATION
+ mtd_register(&priv->mtd, "rwbuffer");
+#endif
+
+ /* Return the implementation-specific state structure as the MTD device */
+
+ fvdbg("Return %p\n", priv);
+ return &priv->mtd;
+}
+
+#endif /* CONFIG_DRVR_WRITEBUFFER || CONFIG_DRVR_READAHEAD */
diff --git a/nuttx/drivers/mtd/smart.c b/nuttx/drivers/mtd/smart.c
index 002a9fe5d..b16f58b68 100644
--- a/nuttx/drivers/mtd/smart.c
+++ b/nuttx/drivers/mtd/smart.c
@@ -105,7 +105,8 @@
* other for our use, such as format
* sector, etc. */
-#if defined(CONFIG_FS_READAHEAD) || (defined(CONFIG_FS_WRITABLE) && defined(CONFIG_FS_WRITEBUFFER))
+#if defined(CONFIG_DRVR_READAHEAD) || (defined(CONFIG_DRVR_WRITABLE) && \
+ defined(CONFIG_DRVR_WRITEBUFFER))
# define CONFIG_SMART_RWBUFFER 1
#endif
diff --git a/nuttx/drivers/rwbuffer.c b/nuttx/drivers/rwbuffer.c
index 0435440dd..c54277ddb 100644
--- a/nuttx/drivers/rwbuffer.c
+++ b/nuttx/drivers/rwbuffer.c
@@ -1,7 +1,7 @@
/****************************************************************************
* drivers/rwbuffer.c
*
- * Copyright (C) 2009, 2011, 2013 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011, 2013-2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -54,7 +54,7 @@
#include <nuttx/wqueue.h>
#include <nuttx/rwbuffer.h>
-#if defined(CONFIG_FS_WRITEBUFFER) || defined(CONFIG_FS_READAHEAD)
+#if defined(CONFIG_DRVR_WRITEBUFFER) || defined(CONFIG_DRVR_READAHEAD)
/****************************************************************************
* Preprocessor Definitions
@@ -66,8 +66,8 @@
# error "Worker thread support is required (CONFIG_SCHED_WORKQUEUE)"
#endif
-#ifndef CONFIG_FS_WRDELAY
-# define CONFIG_FS_WRDELAY 350
+#ifndef CONFIG_DRVR_WRDELAY
+# define CONFIG_DRVR_WRDELAY 350
#endif
/****************************************************************************
@@ -137,7 +137,7 @@ static inline bool rwb_overlap(off_t blockstart1, size_t nblocks1,
* Name: rwb_resetwrbuffer
****************************************************************************/
-#ifdef CONFIG_FS_WRITEBUFFER
+#ifdef CONFIG_DRVR_WRITEBUFFER
static inline void rwb_resetwrbuffer(struct rwbuffer_s *rwb)
{
/* We assume that the caller holds the wrsem */
@@ -152,7 +152,7 @@ static inline void rwb_resetwrbuffer(struct rwbuffer_s *rwb)
* Name: rwb_wrflush
****************************************************************************/
-#ifdef CONFIG_FS_WRITEBUFFER
+#ifdef CONFIG_DRVR_WRITEBUFFER
static void rwb_wrflush(struct rwbuffer_s *rwb)
{
int ret;
@@ -160,7 +160,7 @@ static void rwb_wrflush(struct rwbuffer_s *rwb)
fvdbg("Timeout!\n");
rwb_semtake(&rwb->wrsem);
- if (rwb->wrnblocks)
+ if (rwb->wrnblocks > 0)
{
fvdbg("Flushing: blockstart=0x%08lx nblocks=%d from buffer=%p\n",
(long)rwb->wrblockstart, rwb->wrnblocks, rwb->wrbuffer);
@@ -208,11 +208,11 @@ static void rwb_wrtimeout(FAR void *arg)
static void rwb_wrstarttimeout(FAR struct rwbuffer_s *rwb)
{
- /* CONFIG_FS_WRDELAY provides the delay period in milliseconds. CLK_TCK
+ /* CONFIG_DRVR_WRDELAY provides the delay period in milliseconds. CLK_TCK
* provides the clock tick of the system (frequency in Hz).
*/
- int ticks = (CONFIG_FS_WRDELAY + CLK_TCK/2) / CLK_TCK;
+ int ticks = (CONFIG_DRVR_WRDELAY + CLK_TCK/2) / CLK_TCK;
(void)work_queue(LPWORK, &rwb->work, rwb_wrtimeout, (FAR void *)rwb, ticks);
}
@@ -229,7 +229,7 @@ static inline void rwb_wrcanceltimeout(struct rwbuffer_s *rwb)
* Name: rwb_writebuffer
****************************************************************************/
-#ifdef CONFIG_FS_WRITEBUFFER
+#ifdef CONFIG_DRVR_WRITEBUFFER
static ssize_t rwb_writebuffer(FAR struct rwbuffer_s *rwb,
off_t startblock, uint32_t nblocks,
FAR const uint8_t *wrbuffer)
@@ -265,7 +265,7 @@ static ssize_t rwb_writebuffer(FAR struct rwbuffer_s *rwb,
/* writebuffer is empty? Then initialize it */
- if (!rwb->wrnblocks)
+ if (rwb->wrnblocks == 0)
{
fvdbg("Fresh cache starting at block: 0x%08x\n", startblock);
rwb->wrblockstart = startblock;
@@ -290,7 +290,7 @@ static ssize_t rwb_writebuffer(FAR struct rwbuffer_s *rwb,
* Name: rwb_resetrhbuffer
****************************************************************************/
-#ifdef CONFIG_FS_READAHEAD
+#ifdef CONFIG_DRVR_READAHEAD
static inline void rwb_resetrhbuffer(struct rwbuffer_s *rwb)
{
/* We assume that the caller holds the readAheadBufferSemphore */
@@ -304,7 +304,7 @@ static inline void rwb_resetrhbuffer(struct rwbuffer_s *rwb)
* Name: rwb_bufferread
****************************************************************************/
-#ifdef CONFIG_FS_READAHEAD
+#ifdef CONFIG_DRVR_READAHEAD
static inline void
rwb_bufferread(struct rwbuffer_s *rwb, off_t startblock,
size_t nblocks, uint8_t **rdbuffer)
@@ -338,7 +338,7 @@ rwb_bufferread(struct rwbuffer_s *rwb, off_t startblock,
* Name: rwb_rhreload
****************************************************************************/
-#ifdef CONFIG_FS_READAHEAD
+#ifdef CONFIG_DRVR_READAHEAD
static int rwb_rhreload(struct rwbuffer_s *rwb, off_t startblock)
{
/* Get the block number +1 of the last block that will fit in the
@@ -382,6 +382,231 @@ static int rwb_rhreload(struct rwbuffer_s *rwb, off_t startblock)
#endif
/****************************************************************************
+ * Name: rwb_invalidate_writebuffer
+ *
+ * Description:
+ * Invalidate a region of the write buffer
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DRVR_WRITEBUFFER
+int rwb_invalidate_writebuffer(FAR struct rwbuffer_s *rwb,
+ off_t startblock, size_t blockcount)
+{
+ int ret;
+
+ if (rwb->wrmaxblocks > 0 && wrnblocks > 0)
+ {
+ off_t wrbend;
+ off_t invend;
+
+ fvdbg("startblock=%d blockcount=%p\n", startblock, blockcount);
+
+ rwb_semtake(&rwb->wrsem);
+
+ /* Now there are five cases:
+ *
+ * 1. We invalidate nothing
+ */
+
+ wrbend = rwb->wrblockstart + rwb->wrnblocks;
+ invend = startblock + blockcount;
+
+ if (rwb->wrblockstart > invend || wrbend < startblock)
+ {
+ ret = OK;
+ }
+
+ /* 2. We invalidate the entire write buffer. */
+
+ else if (rwb->wrblockstart >= startblock && wrbend <= invend)
+ {
+ rwb->wrnblocks = 0;
+ ret = OK;
+ }
+
+ /* We are going to invalidate a subset of the write buffer. Three
+ * more cases to consider:
+ *
+ * 2. We invalidate a portion in the middle of the write buffer
+ */
+
+ else if (rwb->wrblockstart < startblock && wrbend > invend)
+ {
+ uint8_t *src;
+ off_t block;
+ off_t offset;
+ size_t nblocks;
+
+ /* Write the blocks at the end of the media to hardware */
+
+ nblocks = wrbend - invend;
+ block = invend;
+ offset = block - rwb->wrblockstart;
+ src = rwb->wrbuffer + offset * rwb->blocksize;
+
+ ret = rwb->wrflush(rwb->dev, block, nblocks, src);
+ if (ret < 0)
+ {
+ fdbg("ERROR: wrflush failed: %d\n", ret);
+ }
+
+ /* Keep the blocks at the beginning of the buffer up the
+ * start of the invalidated region.
+ */
+ else
+ {
+ rwb->wrnblocks = startblock - rwb->wrblockstart;
+ ret = OK;
+ }
+ }
+
+ /* 3. We invalidate a portion at the end of the write buffer */
+
+ else if (wrbend > startblock && wrbend <= invend)
+ {
+ rwb->wrnblocks = wrbend - startblock;
+ ret = OK;
+ }
+
+ /* 4. We invalidate a portion at the beginning of the write buffer */
+
+ else /* if (rwb->wrblockstart >= startblock && wrbend < invend) */
+ {
+ uint8_t *src;
+ size_t ninval;
+ size_t nkeep;
+
+ DEBUGASSERT(rwb->wrblockstart >= startblock && wrbend < invend);
+
+ /* Copy the data from the uninvalidated region to the beginning
+ * of the write buffer.
+ *
+ * First calculate the source and destination of the transfer.
+ */
+
+ ninval = invend - rwb->wrblockstart;
+ src = rwb->wrbuffer + ninval * rwb->blocksize;
+
+ /* Calculate the number of blocks we are keeping. We keep
+ * the ones that we don't invalidate.
+ */
+
+ nkeep = rwb->wrnblocks - ninval;
+
+ /* Then move the data that we are keeping to the beginning
+ * the write buffer.
+ */
+
+ memcpy(rwb->wrbuffer, src, nkeep * rwb->blocksize);
+
+ /* Update the block info. The first block is now the one just
+ * after the invalidation region and the number buffered blocks
+ * is the number that we kept.
+ */
+
+ rwb->wrblockstart = invend;
+ rwb->wrnblocks = nkeep;
+ ret = OK;
+ }
+
+ rwb_semgive(&rwb->wrsem);
+ }
+
+ return ret;
+}
+#endif
+
+/****************************************************************************
+ * Name: rwb_invalidate_readahead
+ *
+ * Description:
+ * Invalidate a region of the read-ahead buffer
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DRVR_READAHEAD
+int rwb_invalidate_readahead(FAR struct rwbuffer_s *rwb,
+ off_t startblock, size_t blockcount)
+{
+ int ret;
+
+ if (rwb->rhmaxblocks > 0 && rhnblocks > 0)
+ {
+ off_t rhbend;
+ off_t invend;
+
+ fvdbg("startblock=%d blockcount=%p\n", startblock, blockcount);
+
+ rwb_semtake(&rwb->rhsem);
+
+ /* Now there are five cases:
+ *
+ * 1. We invalidate nothing
+ */
+
+ rhbend = rwb->rhblockstart + rwb->rhnblocks;
+ invend = startblock + blockcount;
+
+ if (rwb->rhblockstart > invend || rhbend < startblock)
+ {
+ ret = OK;
+ }
+
+ /* 2. We invalidate the entire read-ahead buffer. */
+
+ else if (rwb->rhblockstart >= startblock && rhbend <= invend)
+ {
+ rwb->rhnblocks = 0;
+ ret = OK;
+ }
+
+ /* We are going to invalidate a subset of the read-ahead buffer.
+ * Three more cases to consider:
+ *
+ * 2. We invalidate a portion in the middle of the write buffer
+ */
+
+ else if (rwb->rhblockstart < startblock && rhbend > invend)
+ {
+ /* Keep the blocks at the beginning of the buffer up the
+ * start of the invalidated region.
+ */
+
+ rwb->rhnblocks = startblock - rwb->rhblockstart;
+ ret = OK;
+ }
+
+ /* 3. We invalidate a portion at the end of the read-ahead buffer */
+
+ else if (rhbend > startblock && rhbend <= invend)
+ {
+ rwb->rhnblocks = rhbend - startblock;
+ ret = OK;
+ }
+
+ /* 4. We invalidate a portion at the beginning of the write buffer */
+
+ else /* if (rwb->rhblockstart >= startblock && rhbend < invend) */
+ {
+ /* Let's just force the whole read-ahead buffer to be reloaded.
+ * That might cost s small amount of performance, but well worth
+ * the lower complexity.
+ */
+
+ DEBUGASSERT(rwb->rhblockstart >= startblock && rhbend < invend);
+ rwb->rhnblocks = 0;
+ ret = OK;
+ }
+
+ rwb_semgive(&rwb->rhsem);
+ }
+
+ return ret;
+}
+#endif
+
+/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
@@ -401,71 +626,78 @@ int rwb_initialize(FAR struct rwbuffer_s *rwb)
/* Setup so that rwb_uninitialize can handle a failure */
-#ifdef CONFIG_FS_WRITEBUFFER
+#ifdef CONFIG_DRVR_WRITEBUFFER
DEBUGASSERT(rwb->wrflush!= NULL);
rwb->wrbuffer = NULL;
#endif
-#ifdef CONFIG_FS_READAHEAD
+#ifdef CONFIG_DRVR_READAHEAD
DEBUGASSERT(rwb->rhreload != NULL);
rwb->rhbuffer = NULL;
#endif
-#ifdef CONFIG_FS_WRITEBUFFER
- fvdbg("Initialize the write buffer\n");
+#ifdef CONFIG_DRVR_WRITEBUFFER
+ if (rwb->wrmaxblocks > 0)
+ {
+ fvdbg("Initialize the write buffer\n");
- /* Initialize the write buffer access semaphore */
+ /* Initialize the write buffer access semaphore */
- sem_init(&rwb->wrsem, 0, 1);
+ sem_init(&rwb->wrsem, 0, 1);
- /* Initialize write buffer parameters */
+ /* Initialize write buffer parameters */
- rwb_resetwrbuffer(rwb);
+ rwb_resetwrbuffer(rwb);
- /* Allocate the write buffer */
+ /* Allocate the write buffer */
- rwb->wrbuffer = NULL;
- if (rwb->wrmaxblocks > 0)
- {
- allocsize = rwb->wrmaxblocks * rwb->blocksize;
- rwb->wrbuffer = kmalloc(allocsize);
- if (!rwb->wrbuffer)
+ rwb->wrbuffer = NULL;
+ if (rwb->wrmaxblocks > 0)
{
- fdbg("Write buffer kmalloc(%d) failed\n", allocsize);
- return -ENOMEM;
+ allocsize = rwb->wrmaxblocks * rwb->blocksize;
+ rwb->wrbuffer = kmalloc(allocsize);
+ if (!rwb->wrbuffer)
+ {
+ fdbg("Write buffer kmalloc(%d) failed\n", allocsize);
+ return -ENOMEM;
+ }
}
- }
- fvdbg("Write buffer size: %d bytes\n", allocsize);
-#endif /* CONFIG_FS_WRITEBUFFER */
+ fvdbg("Write buffer size: %d bytes\n", allocsize);
+ }
+#endif /* CONFIG_DRVR_WRITEBUFFER */
-#ifdef CONFIG_FS_READAHEAD
- fvdbg("Initialize the read-ahead buffer\n");
+#ifdef CONFIG_DRVR_READAHEAD
+ if (rhmaxblocks > 0)
+ {
+ fvdbg("Initialize the read-ahead buffer\n");
- /* Initialize the read-ahead buffer access semaphore */
+ /* Initialize the read-ahead buffer access semaphore */
- sem_init(&rwb->rhsem, 0, 1);
+ sem_init(&rwb->rhsem, 0, 1);
- /* Initialize read-ahead buffer parameters */
+ /* Initialize read-ahead buffer parameters */
- rwb_resetrhbuffer(rwb);
+ rwb_resetrhbuffer(rwb);
- /* Allocate the read-ahead buffer */
+ /* Allocate the read-ahead buffer */
- rwb->rhbuffer = NULL;
- if (rwb->rhmaxblocks > 0)
- {
- allocsize = rwb->rhmaxblocks * rwb->blocksize;
- rwb->rhbuffer = kmalloc(allocsize);
- if (!rwb->rhbuffer)
+ rwb->rhbuffer = NULL;
+ if (rwb->rhmaxblocks > 0)
{
- fdbg("Read-ahead buffer kmalloc(%d) failed\n", allocsize);
- return -ENOMEM;
+ allocsize = rwb->rhmaxblocks * rwb->blocksize;
+ rwb->rhbuffer = kmalloc(allocsize);
+ if (!rwb->rhbuffer)
+ {
+ fdbg("Read-ahead buffer kmalloc(%d) failed\n", allocsize);
+ return -ENOMEM;
+ }
}
+
+ fvdbg("Read-ahead buffer size: %d bytes\n", allocsize);
}
+#endif /* CONFIG_DRVR_READAHEAD */
- fvdbg("Read-ahead buffer size: %d bytes\n", allocsize);
-#endif /* CONFIG_FS_READAHEAD */
- return 0;
+ return OK;
}
/****************************************************************************
@@ -474,20 +706,26 @@ int rwb_initialize(FAR struct rwbuffer_s *rwb)
void rwb_uninitialize(FAR struct rwbuffer_s *rwb)
{
-#ifdef CONFIG_FS_WRITEBUFFER
- rwb_wrcanceltimeout(rwb);
- sem_destroy(&rwb->wrsem);
- if (rwb->wrbuffer)
+#ifdef CONFIG_DRVR_WRITEBUFFER
+ if (rwb->wrmaxblocks > 0)
{
- kfree(rwb->wrbuffer);
+ rwb_wrcanceltimeout(rwb);
+ sem_destroy(&rwb->wrsem);
+ if (rwb->wrbuffer)
+ {
+ kfree(rwb->wrbuffer);
+ }
}
#endif
-#ifdef CONFIG_FS_READAHEAD
- sem_destroy(&rwb->rhsem);
- if (rwb->rhbuffer)
+#ifdef CONFIG_DRVR_READAHEAD
+ if (rhmaxblocks > 0)
{
- kfree(rwb->rhbuffer);
+ sem_destroy(&rwb->rhsem);
+ if (rwb->rhbuffer)
+ {
+ kfree(rwb->rhbuffer);
+ }
}
#endif
}
@@ -504,7 +742,7 @@ int rwb_read(FAR struct rwbuffer_s *rwb, off_t startblock, uint32_t nblocks,
fvdbg("startblock=%ld nblocks=%ld rdbuffer=%p\n",
(long)startblock, (long)nblocks, rdbuffer);
-#ifdef CONFIG_FS_WRITEBUFFER
+#ifdef CONFIG_DRVR_WRITEBUFFER
/* If the new read data overlaps any part of the write buffer, then
* flush the write data onto the physical media before reading. We
* could attempt some more exotic handling -- but this simple logic
@@ -522,74 +760,86 @@ int rwb_read(FAR struct rwbuffer_s *rwb, off_t startblock, uint32_t nblocks,
{
rwb_wrflush(rwb);
}
+
rwb_semgive(&rwb->wrsem);
}
#endif
-#ifdef CONFIG_FS_READAHEAD
- /* Loop until we have read all of the requested blocks */
-
- rwb_semtake(&rwb->rhsem);
- for (remaining = nblocks; remaining > 0;)
+#ifdef CONFIG_DRVR_READAHEAD
+ if (rhmaxblocks > 0)
{
- /* Is there anything in the read-ahead buffer? */
+ /* Loop until we have read all of the requested blocks */
- if (rwb->rhnblocks > 0)
+ rwb_semtake(&rwb->rhsem);
+ for (remaining = nblocks; remaining > 0;)
{
- off_t startblock = startblock;
- size_t nbufblocks = 0;
- off_t bufferend;
+ /* Is there anything in the read-ahead buffer? */
- /* Loop for each block we find in the read-head buffer. Count the
- * number of buffers that we can read from read-ahead buffer.
- */
+ if (rwb->rhnblocks > 0)
+ {
+ off_t startblock = startblock;
+ size_t nbufblocks = 0;
+ off_t bufferend;
- bufferend = rwb->rhblockstart + rwb->rhnblocks;
+ /* Loop for each block we find in the read-head buffer. Count
+ * the number of buffers that we can read from read-ahead
+ * buffer.
+ */
- while ((startblock >= rwb->rhblockstart) &&
- (startblock < bufferend) &&
- (remaining > 0))
- {
- /* This is one more that we will read from the read ahead buffer */
+ bufferend = rwb->rhblockstart + rwb->rhnblocks;
- nbufblocks++;
+ while ((startblock >= rwb->rhblockstart) &&
+ (startblock < bufferend) &&
+ (remaining > 0))
+ {
+ /* This is one more that we will read from the read ahead
+ * buffer.
+ */
- /* And one less that we will read from the media */
+ nbufblocks++;
- startblock++;
- remaining--;
- }
+ /* And one less that we will read from the media */
- /* Then read the data from the read-ahead buffer */
+ startblock++;
+ remaining--;
+ }
- rwb_bufferread(rwb, startblock, nbufblocks, &rdbuffer);
- }
+ /* Then read the data from the read-ahead buffer */
- /* If we did not get all of the data from the buffer, then we have to refill
- * the buffer and try again.
- */
+ rwb_bufferread(rwb, startblock, nbufblocks, &rdbuffer);
+ }
- if (remaining > 0)
- {
- int ret = rwb_rhreload(rwb, startblock);
- if (ret < 0)
+ /* If we did not get all of the data from the buffer, then we have
+ * to refill the buffer and try again.
+ */
+
+ if (remaining > 0)
{
- fdbg("ERROR: Failed to fill the read-ahead buffer: %d\n", -ret);
- return ret;
+ int ret = rwb_rhreload(rwb, startblock);
+ if (ret < 0)
+ {
+ fdbg("ERROR: Failed to fill the read-ahead buffer: %d\n", ret);
+ return ret;
+ }
}
}
- }
- /* On success, return the number of blocks that we were requested to read.
- * This is for compatibility with the normal return of a block driver read
- * method
- */
+ /* On success, return the number of blocks that we were requested to
+ * read. This is for compatibility with the normal return of a block
+ * driver read method
+ */
- rwb_semgive(&rwb->rhsem);
- return 0;
+ rwb_semgive(&rwb->rhsem);
+ ret = nblocks;
+ }
+ else
#else
- return rwb->rhreload(rwb->dev, startblock, nblocks, rdbuffer);
+ {
+ ret = rwb->rhreload(rwb->dev, startblock, nblocks, rdbuffer);
+ }
#endif
+
+ return ret;
}
/****************************************************************************
@@ -601,82 +851,135 @@ int rwb_write(FAR struct rwbuffer_s *rwb, off_t startblock,
{
int ret;
-#ifdef CONFIG_FS_READAHEAD
- /* If the new write data overlaps any part of the read buffer, then
- * flush the data from the read buffer. We could attempt some more
- * exotic handling -- but this simple logic is well-suited for simple
- * streaming applications.
- */
-
- rwb_semtake(&rwb->rhsem);
- if (rwb_overlap(rwb->rhblockstart, rwb->rhnblocks, startblock, nblocks))
+#ifdef CONFIG_DRVR_READAHEAD
+ if (rhmaxblocks > 0)
{
- rwb_resetrhbuffer(rwb);
+ /* If the new write data overlaps any part of the read buffer, then
+ * flush the data from the read buffer. We could attempt some more
+ * exotic handling -- but this simple logic is well-suited for simple
+ * streaming applications.
+ */
+
+ rwb_semtake(&rwb->rhsem);
+ if (rwb_overlap(rwb->rhblockstart, rwb->rhnblocks, startblock, nblocks))
+ {
+ rwb_resetrhbuffer(rwb);
+ }
+
+ rwb_semgive(&rwb->rhsem);
}
- rwb_semgive(&rwb->rhsem);
#endif
-#ifdef CONFIG_FS_WRITEBUFFER
- fvdbg("startblock=%d wrbuffer=%p\n", startblock, wrbuffer);
+#ifdef CONFIG_DRVR_WRITEBUFFER
+ if (rwb->wrmaxblocks > 0)
+ {
+ fvdbg("startblock=%d wrbuffer=%p\n", startblock, wrbuffer);
- /* Use the block cache unless the buffer size is bigger than block cache */
+ /* Use the block cache unless the buffer size is bigger than block cache */
- if (nblocks > rwb->wrmaxblocks)
- {
- /* First flush the cache */
+ if (nblocks > rwb->wrmaxblocks)
+ {
+ /* First flush the cache */
- rwb_semtake(&rwb->wrsem);
- rwb_wrflush(rwb);
- rwb_semgive(&rwb->wrsem);
+ rwb_semtake(&rwb->wrsem);
+ rwb_wrflush(rwb);
+ rwb_semgive(&rwb->wrsem);
- /* Then transfer the data directly to the media */
+ /* Then transfer the data directly to the media */
- ret = rwb->wrflush(rwb->dev, startblock, nblocks, wrbuffer);
+ ret = rwb->wrflush(rwb->dev, startblock, nblocks, wrbuffer);
+ }
+ else
+ {
+ /* Buffer the data in the write buffer */
+
+ ret = rwb_writebuffer(rwb, startblock, nblocks, wrbuffer);
+ }
+
+ /* On success, return the number of blocks that we were requested to
+ * write. This is for compatibility with the normal return of a block
+ * driver write method
+ */
}
else
+#else
{
- /* Buffer the data in the write buffer */
+ /* No write buffer.. just pass the write operation through via the
+ * flush callback.
+ */
- ret = rwb_writebuffer(rwb, startblock, nblocks, wrbuffer);
+ ret = rwb->wrflush(rwb->dev, startblock, nblocks, wrbuffer);
}
- /* On success, return the number of blocks that we were requested to write.
- * This is for compatibility with the normal return of a block driver write
- * method
- */
+#endif
return ret;
+}
-#else
+/****************************************************************************
+ * Name: rwb_mediaremoved
+ *
+ * Description:
+ * The following function is called when media is removed
+ *
+ ****************************************************************************/
- return rwb->wrflush(rwb->dev, startblock, nblocks, wrbuffer);
+int rwb_mediaremoved(FAR struct rwbuffer_s *rwb)
+{
+#ifdef CONFIG_DRVR_WRITEBUFFER
+ if (rwb->wrmaxblocks > 0)
+ {
+ rwb_semtake(&rwb->wrsem);
+ rwb_resetwrbuffer(rwb);
+ rwb_semgive(&rwb->wrsem);
+ }
+#endif
+#ifdef CONFIG_DRVR_READAHEAD
+ if (rhmaxblocks > 0)
+ {
+ rwb_semtake(&rwb->rhsem);
+ rwb_resetrhbuffer(rwb);
+ rwb_semgive(&rwb->rhsem);
+ }
#endif
+
+ return OK;
}
/****************************************************************************
- * Name: rwb_mediaremoved
+ * Name: rwb_invalidate
*
* Description:
- * The following function is called when media is removed
+ * Invalidate a region of the caches
*
****************************************************************************/
-int rwb_mediaremoved(FAR struct rwbuffer_s *rwb)
+int rwb_invalidate(FAR struct rwbuffer_s *rwb,
+ off_t startblock, size_t blockcount)
{
-#ifdef CONFIG_FS_WRITEBUFFER
- rwb_semtake(&rwb->wrsem);
- rwb_resetwrbuffer(rwb);
- rwb_semgive(&rwb->wrsem);
+ int ret;
+
+#ifdef CONFIG_DRVR_WRITEBUFFER
+ ret = rwb_invalidate_writebuffer(rwb, startblock, blockcount);
+ if (ret < 0)
+ {
+ fdbg("ERROR: rwb_invalidate_writebuffer failed: %d\n", ret);
+ return ret;
+ }
#endif
-#ifdef CONFIG_FS_READAHEAD
- rwb_semtake(&rwb->rhsem);
- rwb_resetrhbuffer(rwb);
- rwb_semgive(&rwb->rhsem);
+#ifdef CONFIG_DRVR_READAHEAD
+ ret = rwb_invalidate_readahead(rwb, startblock, blockcount);
+ if (ret < 0)
+ {
+ fdbg("ERROR: rwb_invalidate_readahead failed: %d\n", ret);
+ return ret;
+ }
#endif
- return 0;
+
+ return OK;
}
-#endif /* CONFIG_FS_WRITEBUFFER || CONFIG_FS_READAHEAD */
+#endif /* CONFIG_DRVR_WRITEBUFFER || CONFIG_DRVR_READAHEAD */
diff --git a/nuttx/include/nuttx/rwbuffer.h b/nuttx/include/nuttx/rwbuffer.h
index eb7861872..a920c33cc 100644..100755
--- a/nuttx/include/nuttx/rwbuffer.h
+++ b/nuttx/include/nuttx/rwbuffer.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/nuttx/rwbuffer.h
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -33,10 +33,6 @@
*
****************************************************************************/
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
#ifndef __INCLUDE_NUTTX_RWBUFFER_H
#define __INCLUDE_NUTTX_RWBUFFER_H
@@ -51,7 +47,7 @@
#include <semaphore.h>
#include <nuttx/wqueue.h>
-#if defined(CONFIG_FS_WRITEBUFFER) || defined(CONFIG_FS_READAHEAD)
+#if defined(CONFIG_DRVR_WRITEBUFFER) || defined(CONFIG_DRVR_READAHEAD)
/**********************************************************************
* Pre-processor Definitions
@@ -107,45 +103,50 @@ struct rwbuffer_s
uint16_t blocksize; /* The size of one block */
size_t nblocks; /* The total number blocks supported */
- FAR void *dev; /* Device state passed to callout functions */
- /* Write buffer setup. If CONFIG_FS_WRITEBUFFER is defined, but you
- * want read-ahead-only operation, (1) set wrmaxblocks to zero and do
- * not use rwb_write().
+ /* Read-ahead/Write buffer sizes. Buffering can be disabled (even if it
+ * is enabled in the configuration) by setting the buffer size to zero
+ * blocks.
*/
-#ifdef CONFIG_FS_WRITEBUFFER
+#ifdef CONFIG_DRVR_WRITEBUFFER
uint16_t wrmaxblocks; /* The number of blocks to buffer in memory */
- rwbflush_t wrflush; /* Callout to flush the write buffer */
+#endif
+#ifdef CONFIG_DRVR_READAHEAD
+ uint16_t rhmaxblocks; /* The number of blocks to buffer in memory */
#endif
- /* Read-ahead buffer setup. If CONFIG_FS_READAHEAD is defined but you
- * want write-buffer-only operation, then (1) set rhmaxblocks to zero and
- * do not use rwb_read().
+ /* Callback functions.
+ *
+ * wrflush. This callback is normally used to flush the contents of
+ * the write buffer. If write buffering is disabled, then this
+ * function will instead be used to perform unbuffered writes.
+ * rhrelad. This callback is normally used to read new data into the
+ * read-ahead buffer. If read-ahead buffering is disabled, then this
+ * function will instead be used to perform unbuffered reads.
*/
-#ifdef CONFIG_FS_READAHEAD
- uint16_t rhmaxblocks; /* The number of blocks to buffer in memory */
+ FAR void *dev; /* Device state passed to callout functions */
+ rwbflush_t wrflush; /* Callout to flush the write buffer */
rwbreload_t rhreload; /* Callout to reload the read-ahead buffer */
-#endif
/********************************************************************/
- /* The user should never modify any of the remaing fields */
+ /* The user should never modify any of the remaining fields */
- /* This is the state of the write buffer */
+ /* This is the state of the write buffering */
-#ifdef CONFIG_FS_WRITEBUFFER
+#ifdef CONFIG_DRVR_WRITEBUFFER
sem_t wrsem; /* Enforces exclusive access to the write buffer */
- struct work_s work; /* Delayed work to flush buffer after adelay with no activity */
+ struct work_s work; /* Delayed work to flush buffer after a delay with no activity */
uint8_t *wrbuffer; /* Allocated write buffer */
uint16_t wrnblocks; /* Number of blocks in write buffer */
off_t wrblockstart; /* First block in write buffer */
off_t wrexpectedblock; /* Next block expected */
#endif
- /* This is the state of the read-ahead buffer */
+ /* This is the state of the read-ahead buffering */
-#ifdef CONFIG_FS_READAHEAD
+#ifdef CONFIG_DRVR_READAHEAD
sem_t rhsem; /* Enforces exclusive access to the write buffer */
uint8_t *rhbuffer; /* Allocated read-ahead buffer */
uint16_t rhnblocks; /* Number of blocks in read-ahead buffer */
@@ -160,7 +161,8 @@ struct rwbuffer_s
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN EXTERN "C"
-EXTERN "C" {
+EXTERN "C"
+{
#else
#define EXTERN extern
#endif
@@ -171,22 +173,32 @@ EXTERN "C" {
/* Buffer initialization */
-EXTERN int rwb_initialize(FAR struct rwbuffer_s *rwb);
-EXTERN void rwb_uninitialize(FAR struct rwbuffer_s *rwb);
+int rwb_initialize(FAR struct rwbuffer_s *rwb);
+void rwb_uninitialize(FAR struct rwbuffer_s *rwb);
+
+/* Block oriented transfers */
+
+ssize_t rwb_read(FAR struct rwbuffer_s *rwb, off_t startblock,
+ size_t blockcount, FAR uint8_t *rdbuffer);
+ssize_t rwb_write(FAR struct rwbuffer_s *rwb,
+ off_t startblock, size_t blockcount,
+ FAR const uint8_t *wrbuffer);
+
+/* Character oriented transfers */
+
+ssize_t mtd_readbytes(FAR struct rwbuffer_s *dev, off_t offset,
+ size_t nbytes, FAR uint8_t *buffer);
-/* Buffer transfers */
+/* Media events */
-EXTERN ssize_t rwb_read(FAR struct rwbuffer_s *rwb, off_t startblock,
- size_t blockcount, FAR uint8_t *rdbuffer);
-EXTERN ssize_t rwb_write(FAR struct rwbuffer_s *rwb,
- off_t startblock, size_t blockcount,
- FAR const uint8_t *wrbuffer);
-EXTERN int rwb_mediaremoved(FAR struct rwbuffer_s *rwb);
+int rwb_mediaremoved(FAR struct rwbuffer_s *rwb);
+int rwb_invalidate(FAR struct rwbuffer_s *rwb,
+ off_t startblock, size_t blockcount);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
-#endif /* CONFIG_FS_WRITEBUFFER || CONFIG_READAHEAD_BUFFER */
+#endif /* CONFIG_DRVR_WRITEBUFFER || CONFIG_DRVR_READAHEAD */
#endif /* __INCLUDE_NUTTX_RWBUFFER_H */