summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog5
-rw-r--r--nuttx/Documentation/NuttX.html6
-rwxr-xr-xnuttx/arch/arm/src/stm32/stm32_internal.h34
-rwxr-xr-xnuttx/configs/stm3210e-eval/src/stm3210e-internal.h4
-rw-r--r--nuttx/drivers/Makefile17
-rw-r--r--nuttx/drivers/README.txt10
-rw-r--r--nuttx/drivers/mtd/Make.defs38
-rw-r--r--nuttx/drivers/mtd/m25px.c562
-rw-r--r--nuttx/drivers/mtd/skeleton.c234
-rw-r--r--nuttx/include/nuttx/ioctl.h9
-rw-r--r--nuttx/include/nuttx/mtd.h128
-rw-r--r--nuttx/include/nuttx/spi.h6
12 files changed, 1023 insertions, 30 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 617a1c264..e08bd7783 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -915,3 +915,8 @@
0.4.13 2009-xx-xx Gregory Nutt <spudmonkey@racsa.co.cr>
+ * include/nuttx/mtd.h. Added a simple interface definition to support some
+ FLASH, EEPROM, NVRAM, etc. devices.
+ * driver/mtd/m25px.c. Added a driver for SPI based FLASH parts M25P64 and M25P128.
+
+
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index 382faeb87..8d725e535 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -8,7 +8,7 @@
<tr align="center" bgcolor="#e4e4e4">
<td>
<h1><big><font color="#3c34ec"><i>NuttX RTOS</i></font></big></h1>
- <p>Last Updated: October 17, 2009</p>
+ <p>Last Updated: October 18, 2009</p>
</td>
</tr>
</table>
@@ -1567,6 +1567,10 @@ buildroot-0.1.7 2009-06-26 &lt;spudmonkey@racsa.co.cr&gt;
<ul><pre>
nuttx-0.4.13 2009-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
+ * include/nuttx/mtd.h. Added a simple interface definition to support some
+ FLASH, EEPROM, NVRAM, etc. devices.
+ * driver/mtd/m25px.c. Added a driver for SPI based FLASH parts M25P64 and M25P128.
+
pascal-0.1.3 2009-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
buildroot-0.1.8 2009-xx-xx &lt;spudmonkey@racsa.co.cr&gt;
diff --git a/nuttx/arch/arm/src/stm32/stm32_internal.h b/nuttx/arch/arm/src/stm32/stm32_internal.h
index b558ce2a5..e5d429be7 100755
--- a/nuttx/arch/arm/src/stm32/stm32_internal.h
+++ b/nuttx/arch/arm/src/stm32/stm32_internal.h
@@ -124,23 +124,23 @@
* .... .... .... .... .... .... .... BBBB
*/
-#define GPIO_PIN_SHIFT 0 /* Bits 0-3: GPIO number: 0-15 */
-#define GPIO_PIN_MASK (15 << GPIO_PIN_SHIFT)
-#define GPIO_PIN1 (1 << GPIO_PIN_SHIFT)
-#define GPIO_PIN2 (2 << GPIO_PIN_SHIFT)
-#define GPIO_PIN3 (3 << GPIO_PIN_SHIFT)
-#define GPIO_PIN4 (4 << GPIO_PIN_SHIFT)
-#define GPIO_PIN5 (5 << GPIO_PIN_SHIFT)
-#define GPIO_PIN6 (6 << GPIO_PIN_SHIFT)
-#define GPIO_PIN7 (7 << GPIO_PIN_SHIFT)
-#define GPIO_PIN8 (8 << GPIO_PIN_SHIFT)
-#define GPIO_PIN9 (9 << GPIO_PIN_SHIFT)
-#define GPIO_PIN10 (10 << GPIO_PIN_SHIFT)
-#define GPIO_PIN11 (11 << GPIO_PIN_SHIFT)
-#define GPIO_PIN12 (12 << GPIO_PIN_SHIFT)
-#define GPIO_PIN13 (13 << GPIO_PIN_SHIFT)
-#define GPIO_PIN14 (14 << GPIO_PIN_SHIFT)
-#define GPIO_PIN15 (15 << GPIO_PIN_SHIFT)
+#define GPIO_PIN_SHIFT 0 /* Bits 0-3: GPIO number: 0-15 */
+#define GPIO_PIN_MASK (15 << GPIO_PIN_SHIFT)
+#define GPIO_PIN1 (1 << GPIO_PIN_SHIFT)
+#define GPIO_PIN2 (2 << GPIO_PIN_SHIFT)
+#define GPIO_PIN3 (3 << GPIO_PIN_SHIFT)
+#define GPIO_PIN4 (4 << GPIO_PIN_SHIFT)
+#define GPIO_PIN5 (5 << GPIO_PIN_SHIFT)
+#define GPIO_PIN6 (6 << GPIO_PIN_SHIFT)
+#define GPIO_PIN7 (7 << GPIO_PIN_SHIFT)
+#define GPIO_PIN8 (8 << GPIO_PIN_SHIFT)
+#define GPIO_PIN9 (9 << GPIO_PIN_SHIFT)
+#define GPIO_PIN10 (10 << GPIO_PIN_SHIFT)
+#define GPIO_PIN11 (11 << GPIO_PIN_SHIFT)
+#define GPIO_PIN12 (12 << GPIO_PIN_SHIFT)
+#define GPIO_PIN13 (13 << GPIO_PIN_SHIFT)
+#define GPIO_PIN14 (14 << GPIO_PIN_SHIFT)
+#define GPIO_PIN15 (15 << GPIO_PIN_SHIFT)
/* Alternate Pin Functions: */
diff --git a/nuttx/configs/stm3210e-eval/src/stm3210e-internal.h b/nuttx/configs/stm3210e-eval/src/stm3210e-internal.h
index aeceef6fb..ac5d7ddb7 100755
--- a/nuttx/configs/stm3210e-eval/src/stm3210e-internal.h
+++ b/nuttx/configs/stm3210e-eval/src/stm3210e-internal.h
@@ -72,11 +72,11 @@
/* MMC/SD SPI1 chip select: PC.12 */
-#define GPIO_MMCSD_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN12)
+#define GPIO_MMCSD_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN12)
/* SPI FLASH chip select: PA.4 */
-#define GPIO_FLASH_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN4)
+#define GPIO_FLASH_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
/************************************************************************************
* Public Functions
diff --git a/nuttx/drivers/Makefile b/nuttx/drivers/Makefile
index 9155aedc1..2afd27f2f 100644
--- a/nuttx/drivers/Makefile
+++ b/nuttx/drivers/Makefile
@@ -78,17 +78,23 @@ CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/driv
endif
endif
-ASRCS = $(SERIAL_ASRCS) $(NET_ASRCS) $(PIPE_ASRCS) $(USBDEV_ASRCS) $(MMCSD_ASRCS) $(BCH_ASRCS)
+include mtd/Make.defs
+ROOTDEPPATH = --dep-path .
+MTDDEPPATH = --dep-path mtd
+
+ASRCS = $(SERIAL_ASRCS) $(NET_ASRCS) $(PIPE_ASRCS) $(USBDEV_ASRCS) \
+ $(MMCSD_ASRCS) $(BCH_ASRCS) $(MTD_ASRCS)
AOBJS = $(ASRCS:.S=$(OBJEXT))
CSRCS =
ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
CSRCS += dev_null.c dev_zero.c loop.c can.c
ifneq ($(CONFIG_DISABLE_MOUNTPOINT),y)
-CSRCS += ramdisk.c
+CSRCS += ramdisk.c
endif
endif
-CSRCS += $(SERIAL_CSRCS) $(NET_CSRCS) $(PIPE_CSRCS) $(USBDEV_CSRCS) $(MMCSD_CSRCS) $(BCH_CSRCS)
+CSRCS += $(SERIAL_CSRCS) $(NET_CSRCS) $(PIPE_CSRCS) $(USBDEV_CSRCS) \
+ $(MMCSD_CSRCS) $(BCH_CSRCS) $(MTD_CSRCS)
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
@@ -96,7 +102,7 @@ OBJS = $(AOBJS) $(COBJS)
BIN = libdrivers$(LIBEXT)
-VPATH = serial:net:pipes:usbdev:mmcsd:bch
+VPATH = serial:net:pipes:usbdev:mmcsd:bch:mtd
all: $(BIN)
@@ -112,7 +118,8 @@ $(BIN): $(OBJS)
done ; )
.depend: Makefile $(SRCS)
- @$(MKDEP) $(ROOTDEPPATH) $(SERIALDEPPATH) $(NETDEPPATH) $(PIPEDEPPATH)$(USBDEVDEPPATH) $(MMCSDDEPPATH) $(BCHDEPPATH) \
+ @$(MKDEP) $(ROOTDEPPATH) $(SERIALDEPPATH) $(NETDEPPATH) $(PIPEDEPPATH) \
+ $(USBDEVDEPPATH) $(MMCSDDEPPATH) $(BCHDEPPATH) $(MTDDEPPATH) \
$(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
@touch $@
diff --git a/nuttx/drivers/README.txt b/nuttx/drivers/README.txt
index c7e42c9a7..2a0f96684 100644
--- a/nuttx/drivers/README.txt
+++ b/nuttx/drivers/README.txt
@@ -39,6 +39,16 @@ mmcsd/
Support for MMC/SD block drivers. At present, only SPI-based
MMC/SD is supported. See include/nuttx/mmcsd.h.
+mtd/
+ Memory Technology Device (MTD) drivers. Some simple drivers for
+ memory technologies like FLASH, EEPROM, NVRAM, etc. See
+ include/nuttx/mtd.h
+
+ (Note: This is a simple memory interface and should not be
+ confused with the "real" MTD developed at infradead.org. This
+ logic is unrelated; I just used the name MTD because I am not
+ aware of any other common way to refer to this class of devices).
+
net/
Network interface drivers. See also include/nuttx/net.h
diff --git a/nuttx/drivers/mtd/Make.defs b/nuttx/drivers/mtd/Make.defs
new file mode 100644
index 000000000..ff5b0a225
--- /dev/null
+++ b/nuttx/drivers/mtd/Make.defs
@@ -0,0 +1,38 @@
+############################################################################
+# drivers/mtd/Make.defs
+#
+# Copyright (C) 2009 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.
+#
+############################################################################
+
+MTD_ASRCS =
+MTD_CSRCS = m25px.c
+
diff --git a/nuttx/drivers/mtd/m25px.c b/nuttx/drivers/mtd/m25px.c
new file mode 100644
index 000000000..1ab71f877
--- /dev/null
+++ b/nuttx/drivers/mtd/m25px.c
@@ -0,0 +1,562 @@
+/************************************************************************************
+ * drivers/mtd/m25px.c
+ * Driver for SPI-based M25P64 (64Mbit) and M25P128 (128Mbit) FLASH
+ *
+ * Copyright (C) 2009 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 <stdlib.h>
+#include <errno.h>
+
+#include <nuttx/ioctl.h>
+#include <nuttx/spi.h>
+#include <nuttx/mtd.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Indentification register values */
+
+#define M25P_MANUFACTURER 0x20
+#define M25P_MEMORY_TYPE 0x20
+#define M25P_M25P64_CAPACITY 0x17 /* 64 M-bit */
+#define M25P_M25P128_CAPACITY 0x18 /* 128 M-bit */
+
+/* M25P64 capapcity is 8,338,608 bytes:
+ * (128 sectors) * (65,536 bytes per sector)
+ * (32768 pages) * (256 bytes per page)
+ */
+
+#define M25P_M25P64_SECTOR_SHIFT 16 /* Sector size 1 << 16 = 65,536 */
+#define M25P_M25P64_NSECTORS 128
+#define M25P_M25P64_PAGE_SHIFT 8 /* Page size 1 << 8 = 256 */
+#define M25P_M25P64_NPAGES 32768
+
+/* M25P64 capapcity is 16,777,216 bytes:
+ * (64 sectors) * (262,144 bytes per sector)
+ * (65536 pages) * (256 bytes per page)
+ */
+
+#define M25P_M25P128_SECTOR_SHIFT 18 /* Sector size 1 << 18 = 262,144 */
+#define M25P_M25P128_NSECTORS 64
+#define M25P_M25P128_PAGE_SHIFT 8 /* Page size 1 << 8 = 256 */
+#define M25P_M25P128_NPAGES 65536
+
+/* Instructions */
+/* Command Value N Description Addr Dummy Data */
+#define M25P_WREN 0x06 /* 1 Write Enable 0 0 0 */
+#define M25P_WRDI 0x04 /* 1 Write Disable 0 0 0 */
+#define M25P_RDID 0x9f /* 1 Read Identification 0 0 1-3 */
+#define M25P_RDSR 0x05 /* 1 Read Status Register 0 0 >=1 */
+#define M25P_WRSR 0x01 /* 1 Write Status Register 0 0 1 */
+#define M25P_READ 0x03 /* 1 Read Data Bytes 3 0 >=1 */
+#define M25P_FAST_READ 0x0b /* 1 Higher speed read 3 1 >=1 */
+#define M25P_PP 0x02 /* 1 Page Program 3 0 1-256 */
+#define M25P_SE 0xd8 /* 1 Sector Erase 3 0 0 */
+#define M25P_BE 0xc7 /* 1 Bulk Erase 0 0 0 */
+#define M25P_RES 0xab /* 2 Read Electronic Signature 0 3 >=1 */
+
+/* NOTE 1: Both parts, NOTE 2: M25P64 only */
+
+/* Status register bit definitions */
+
+#define M25P_SR_WIP (1 << 0) /* Bit 0: Write in progress bit */
+#define M25P_SR_WEL (1 << 1) /* Bit 1: Write enable latch bit */
+#define M25P_SR_BP_SHIFT (2) /* Bits 2-4: Block protect bits */
+#define M25P_SR_BP_MASK (7 << M25P_SR_BP_SHIFT)
+# define M25P_SR_BP_NONE (0 << M25P_SR_BP_SHIFT) /* Unprotected */
+# define M25P_SR_BP_UPPER64th (1 << M25P_SR_BP_SHIFT) /* Upper 64th */
+# define M25P_SR_BP_UPPER32nd (2 << M25P_SR_BP_SHIFT) /* Upper 32nd */
+# define M25P_SR_BP_UPPER16th (3 << M25P_SR_BP_SHIFT) /* Upper 16th */
+# define M25P_SR_BP_UPPER8th (4 << M25P_SR_BP_SHIFT) /* Upper 8th */
+# define M25P_SR_BP_UPPERQTR (5 << M25P_SR_BP_SHIFT) /* Upper quarter */
+# define M25P_SR_BP_UPPERHALF (6 << M25P_SR_BP_SHIFT) /* Upper half */
+# define M25P_SR_BP_ALL (7 << M25P_SR_BP_SHIFT) /* All sectors */
+#define M25P_SR_SRWD (1 << 7) /* Bit 7: Status register write protect */
+
+#define M25P_DUMMY 0xa5
+
+/************************************************************************************
+ * 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 m25p_dev_s.
+ */
+
+struct m25p_dev_s
+{
+ struct mtd_dev_s mtd; /* MTD interface */
+ FAR struct spi_dev_s *dev; /* Saved SPI interface instance */
+ ubyte sectorshift; /* 16 or 18 */
+ ubyte pageshift; /* 8 */
+ uint16 nsectors; /* 128 or 64 */
+ uint32 npages; /* 32,768 or 65,536 */
+};
+
+/************************************************************************************
+ * Private Function Prototypes
+ ************************************************************************************/
+
+/* Helpers */
+
+static inline int m25p_readid(struct m25p_dev_s *priv);
+static void m25p_waitwritecomplete(struct m25p_dev_s *priv);
+static void m25p_writeenable(struct m25p_dev_s *priv);
+static inline void m25p_sectorerase(struct m25p_dev_s *priv, off_t address);
+static inline void m25p_pagewrite(struct m25p_dev_s *priv, FAR const ubyte *buffer,
+ off_t address);
+
+/* MTD driver methods */
+
+static int m25p_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks);
+static int m25p_read(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR ubyte *buf);
+static int m25p_write(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR const ubyte *buf);
+static int m25p_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg);
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: m25p_readid
+ ************************************************************************************/
+
+static inline int m25p_readid(struct m25p_dev_s *priv)
+{
+ uint16 manufacturer;
+ uint16 memory;
+ uint16 capacity;
+
+ /* Select this FLASH part. This is a blocking call and will not return
+ * until we have exclusiv access to the SPI buss. We will retain that
+ * exclusive access until the chip is de-selected.
+ */
+
+ SPI_SELECT(priv->dev, SPIDEV_FLASH, TRUE);
+
+ /* Send the "Read ID (RDID)" command and read the first three ID bytes */
+
+ (void)SPI_SEND(priv->dev, M25P_RDID);
+ manufacturer = SPI_SEND(priv->dev, M25P_DUMMY);
+ memory = SPI_SEND(priv->dev, M25P_DUMMY);
+ capacity = SPI_SEND(priv->dev, M25P_DUMMY);
+
+ /* Deselect the FLASH */
+
+ SPI_SELECT(priv->dev, SPIDEV_FLASH, FALSE);
+
+ /* Check for a valid manufacturer and memory type */
+
+ if (manufacturer == M25P_MANUFACTURER && memory == M25P_MEMORY_TYPE)
+ {
+ /* Okay.. is it a FLASH capacity that we understand? */
+
+ if (capacity == M25P_M25P64_CAPACITY)
+ {
+ /* Save the FLASH geometry */
+
+ priv->sectorshift = M25P_M25P64_SECTOR_SHIFT;
+ priv->nsectors = M25P_M25P64_NSECTORS;
+ priv->pageshift = M25P_M25P64_PAGE_SHIFT;
+ priv->npages = M25P_M25P64_NPAGES;
+ return OK;
+ }
+ else if (capacity == M25P_M25P128_CAPACITY)
+ {
+ priv->sectorshift = M25P_M25P128_SECTOR_SHIFT;
+ priv->nsectors = M25P_M25P128_NSECTORS;
+ priv->pageshift = M25P_M25P128_PAGE_SHIFT;
+ priv->npages = M25P_M25P128_NPAGES;
+ return OK;
+ }
+ }
+
+ return -ENODEV;
+}
+
+/************************************************************************************
+ * Name: m25p_waitwritecomplete
+ ************************************************************************************/
+
+static void m25p_waitwritecomplete(struct m25p_dev_s *priv)
+{
+ ubyte status;
+
+ /* Select this FLASH part. This is a blocking call and will not return
+ * until we have exclusiv access to the SPI buss. We will retain that
+ * exclusive access until the chip is de-selected.
+ */
+
+ SPI_SELECT(priv->dev, SPIDEV_FLASH, TRUE);
+
+ /* Send "Read Status Register (RDSR)" command */
+
+ (void)SPI_SEND(priv->dev, M25P_RDSR);
+
+ /* Loop as long as the memory is busy with a write cycle */
+
+ do
+ {
+ /* Send a dummy byte to generate the clock needed to shift out the status */
+
+ status = SPI_SEND(priv->dev, M25P_DUMMY);
+ }
+ while ((status & M25P_SR_WIP) != 0);
+
+ /* Deselect the FLASH */
+
+ SPI_SELECT(priv->dev, SPIDEV_FLASH, FALSE);
+}
+
+/************************************************************************************
+ * Name: m25p_writeenable
+ ************************************************************************************/
+
+static void m25p_writeenable(struct m25p_dev_s *priv)
+{
+ /* Select this FLASH part. This is a blocking call and will not return
+ * until we have exclusiv access to the SPI buss. We will retain that
+ * exclusive access until the chip is de-selected.
+ */
+
+ SPI_SELECT(priv->dev, SPIDEV_FLASH, TRUE);
+
+ /* Send "Write Enable (WREN)" command */
+
+ (void)SPI_SEND(priv->dev, M25P_WREN);
+
+ /* Deselect the FLASH */
+
+ SPI_SELECT(priv->dev, SPIDEV_FLASH, FALSE);
+}
+
+/************************************************************************************
+ * Name: m25p_sectorerase
+ ************************************************************************************/
+
+static inline void m25p_sectorerase(struct m25p_dev_s *priv, off_t sector)
+{
+ off_t address = sector << priv->sectorshift;
+
+ /* Wait for any preceding write to complete. We could simplify things by
+ * perform this wait at the end of each write operation (rather than at
+ * the beginning of ALL operations), but have the wait first will slightly
+ * improve performance.
+ */
+
+ m25p_waitwritecomplete(priv);
+
+ /* Send write enable instruction */
+
+ m25p_writeenable(priv);
+
+ /* Select this FLASH part. This is a blocking call and will not return
+ * until we have exclusiv access to the SPI buss. We will retain that
+ * exclusive access until the chip is de-selected.
+ */
+
+ SPI_SELECT(priv->dev, SPIDEV_FLASH, TRUE);
+
+ /* Send the "Sector Erase (SE)" instruction */
+
+ (void)SPI_SEND(priv->dev, M25P_SE);
+
+ /* Send the sector address high byte first. For all of the supported
+ * parts, the sector number is completely contained in the first byte
+ * and the values used in the following two bytes don't really matter.
+ */
+
+ (void)SPI_SEND(priv->dev, (address >> 16) & 0xff);
+ (void)SPI_SEND(priv->dev, (address >> 8) & 0xff);
+ (void)SPI_SEND(priv->dev, address & 0xff);
+
+ /* Deselect the FLASH */
+
+ SPI_SELECT(priv->dev, SPIDEV_FLASH, FALSE);
+}
+
+/************************************************************************************
+ * Name: m25p_pagewrite
+ ************************************************************************************/
+
+static inline void m25p_pagewrite(struct m25p_dev_s *priv, FAR const ubyte *buffer,
+ off_t page)
+{
+ off_t address = page << priv->pageshift;
+
+ /* Wait for any preceding write to complete. We could simplify things by
+ * perform this wait at the end of each write operation (rather than at
+ * the beginning of ALL operations), but have the wait first will slightly
+ * improve performance.
+ */
+
+ m25p_waitwritecomplete(priv);
+
+ /* Enable the write access to the FLASH */
+
+ m25p_writeenable(priv);
+
+ /* Select this FLASH part. This is a blocking call and will not return
+ * until we have exclusiv access to the SPI buss. We will retain that
+ * exclusive access until the chip is de-selected.
+ */
+
+ SPI_SELECT(priv->dev, SPIDEV_FLASH, TRUE);
+
+ /* Send "Page Program (PP)" command */
+
+ (void)SPI_SEND(priv->dev, M25P_PP);
+
+ /* Send the page address high byte first. */
+
+ (void)SPI_SEND(priv->dev, (address >> 16) & 0xff);
+ (void)SPI_SEND(priv->dev, (address >> 8) & 0xff);
+ (void)SPI_SEND(priv->dev, address & 0xff);
+
+ /* Then write the specified number of bytes */
+
+ SPI_SNDBLOCK(priv->dev, buffer, 1 << priv->pageshift);
+
+ /* Deselect the FLASH: Chip Select high */
+
+ SPI_SELECT(priv->dev, SPIDEV_FLASH, FALSE);
+}
+
+/************************************************************************************
+ * Name: m25p_erase
+ ************************************************************************************/
+
+static int m25p_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks)
+{
+ FAR struct m25p_dev_s *priv = (FAR struct m25p_dev_s *)dev;
+ size_t blocksleft = nblocks;
+
+ while (blocksleft-- > 0)
+ {
+ m25p_sectorerase(priv, startblock);
+ startblock++;
+ }
+
+ return (int)nblocks;
+}
+
+/************************************************************************************
+ * Name: m25p_read
+ ************************************************************************************/
+
+static int m25p_read(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR ubyte *buffer)
+{
+ FAR struct m25p_dev_s *priv = (FAR struct m25p_dev_s *)dev;
+ off_t address;
+
+ /* Convert the sector address and count to byte-oriented values */
+
+ address = startblock << priv->pageshift;
+
+ /* Wait for any preceding write to complete. We could simplify things by
+ * perform this wait at the end of each write operation (rather than at
+ * the beginning of ALL operations), but have the wait first will slightly
+ * improve performance.
+ */
+
+ m25p_waitwritecomplete(priv);
+
+ /* Select this FLASH part. This is a blocking call and will not return
+ * until we have exclusiv access to the SPI buss. We will retain that
+ * exclusive access until the chip is de-selected.
+ */
+
+ SPI_SELECT(priv->dev, SPIDEV_FLASH, TRUE);
+
+ /* Send "Read from Memory " instruction */
+
+ (void)SPI_SEND(priv->dev, M25P_READ);
+
+ /* Send the page address high byte first. */
+
+ (void)SPI_SEND(priv->dev, (address >> 16) & 0xff);
+ (void)SPI_SEND(priv->dev, (address >> 8) & 0xff);
+ (void)SPI_SEND(priv->dev, address & 0xff);
+
+ /* Then read all of the requested bytes */
+
+ SPI_RECVBLOCK(priv->dev, buffer, nblocks << priv->pageshift);
+
+ /* Deselect the FLASH */
+
+ SPI_SELECT(priv->dev, SPIDEV_FLASH, FALSE);
+ return nblocks;
+}
+
+/************************************************************************************
+ * Name: m25p_write
+ ************************************************************************************/
+
+static int m25p_write(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR const ubyte *buffer)
+{
+ FAR struct m25p_dev_s *priv = (FAR struct m25p_dev_s *)dev;
+ size_t blocksleft = nblocks;
+
+ /* Write each page to FLASH */
+
+ while (blocksleft-- > 0)
+ {
+ m25p_pagewrite(priv, buffer, startblock);
+ startblock++;
+ }
+
+ return nblocks;
+}
+
+/************************************************************************************
+ * Name: m25p_ioctl
+ ************************************************************************************/
+
+static int m25p_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
+{
+ FAR struct m25p_dev_s *priv = (FAR struct m25p_dev_s *)dev;
+ int ret = -EINVAL; /* Assume good command with bad parameters */
+
+ switch (cmd)
+ {
+ case MTDIOC_GEOMETRY:
+ {
+ FAR struct mtd_geometry_s *geo = (FAR struct mtd_geometry_s *)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 = (1 << priv->pageshift);
+ geo->erasesize = (1 << priv->sectorshift);
+ geo->neraseblocks = priv->nsectors;
+ ret = OK;
+ }
+ }
+ break;
+
+ case MTDIOC_XIPBASE:
+ default:
+ ret = -ENOTTY; /* Bad command */
+ break;
+ }
+
+ return ret;
+}
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: m25p_initialize
+ *
+ * Description:
+ * Create an initialize MTD device instance. 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 *m25p_initialize(FAR struct spi_dev_s *dev)
+{
+ FAR struct m25p_dev_s *priv;
+ int ret;
+
+ /* 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 m25p_dev_s *)malloc(sizeof(struct m25p_dev_s));
+ if (priv)
+ {
+ /* Initialize the allocated structure */
+
+ priv->mtd.erase = m25p_erase;
+ priv->mtd.read = m25p_read;
+ priv->mtd.write = m25p_write;
+ priv->mtd.ioctl = m25p_ioctl;
+ priv->dev = dev;
+
+ /* Deselect the FLASH */
+
+ SPI_SELECT(dev, SPIDEV_FLASH, FALSE);
+
+ /* Make sure that SPI is correctly configured from this FLASH */
+
+ SPI_SETMODE(dev, SPIDEV_MODE3);
+ SPI_SETBITS(dev, 8);
+ SPI_SETFREQUENCY(dev, 20000000);
+
+ /* Identify the FLASH chip and get its capacity */
+
+ ret = m25p_readid(priv);
+ if (ret != OK)
+ {
+ /* Unrecognized! Discard all of that work we just did and return NULL */
+
+ free(priv);
+ priv = NULL;
+ }
+ }
+
+ /* Return the implementation-specific state structure as the MTD device */
+
+ return (FAR struct mtd_dev_s *)priv;
+}
diff --git a/nuttx/drivers/mtd/skeleton.c b/nuttx/drivers/mtd/skeleton.c
new file mode 100644
index 000000000..84df9ffe0
--- /dev/null
+++ b/nuttx/drivers/mtd/skeleton.c
@@ -0,0 +1,234 @@
+/****************************************************************************
+ * drivers/mtd/skeleton.c
+ *
+ * Copyright (C) 2009 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 <errno.h>
+
+#include <nuttx/ioctl.h>
+#include <nuttx/mtd.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * 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 skel_dev_s.
+ */
+
+struct skel_dev_s
+{
+ struct mtd_dev_s mtd;
+
+ /* Other implementation specific data may follow here */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/* MTD driver methods */
+
+static int skel_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks);
+static int skel_read(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR ubyte *buf);
+static int skel_write(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR const ubyte *buf);
+static int skel_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static struct skel_dev_s g_skeldev =
+{
+ { skel_erase, skel_read, skel_write, skel_ioctl },
+ /* Initialization of any other implemenation specific data goes here */
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: skel_erase
+ ****************************************************************************/
+
+static int skel_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks)
+{
+ FAR struct skel_dev_s *priv = (FAR struct skel_dev_s *)dev;
+
+ /* The interface definition assumes that all erase blocks ar the same size.
+ * If that is not true for this particular device, then transform the
+ * start block and nblocks as necessary.
+ */
+
+ /* Erase the specified blocks and return status (OK or a negated errno) */
+
+ return OK;
+}
+
+/****************************************************************************
+ * Name: skel_read
+ ****************************************************************************/
+
+static int skel_read(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR ubyte *buf)
+{
+ FAR struct skel_dev_s *priv = (FAR struct skel_dev_s *)dev;
+
+ /* The interface definition assumes that all read/write blocks ar the same size.
+ * If that is not true for this particular device, then transform the
+ * start block and nblocks as necessary.
+ */
+
+ /* Read the specified blocks into the provided user buffer and return status
+ * (The positive, number of blocks actually read or a negated errno)
+ */
+
+ return 0;
+}
+
+/****************************************************************************
+ * Name: skel_write
+ ****************************************************************************/
+
+static int skel_write(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR const ubyte *buf)
+{
+ FAR struct skel_dev_s *priv = (FAR struct skel_dev_s *)dev;
+
+ /* The interface definition assumes that all read/write blocks ar the same size.
+ * If that is not true for this particular device, then transform the
+ * start block and nblocks as necessary.
+ */
+
+ /* Write the specified blocks from the provided user buffer and return status
+ * (The positive, number of blocks actually written or a negated errno)
+ */
+
+ return 0;
+}
+
+/****************************************************************************
+ * Name: skel_ioctl
+ ****************************************************************************/
+
+static int skel_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
+{
+ FAR struct skel_dev_s *priv = (FAR struct skel_dev_s *)dev;
+ int ret = -EINVAL; /* Assume good command with bad parameters */
+
+ switch (cmd)
+ {
+ case MTDIOC_GEOMETRY:
+ {
+ FAR struct mtd_geometry_s *geo = (FARstruct mtd_geometry_s *)arg;
+ if (ppv)
+ {
+ /* 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 = 512; /* Size of one read/write block */
+ geo->erasesize = 4096; /* Size of one erase block */
+ geo->neraseblocks = 1024; /* Number of erase blocks */
+ ret = OK;
+ }
+ }
+ break;
+
+ case MTDIOC_XIPBASE:
+ {
+ FAR void **ppv = (FAR void**)arg;
+
+ if (ppv)
+ {
+ /* If media is directly acccesible, return (void*) base address
+ * of device memory. NULL otherwise. It is acceptable to omit
+ * this case altogether and simply return -ENOTTY.
+ */
+
+ *ppv = NULL;
+ ret = OK;
+ }
+ }
+ break;
+
+ default:
+ ret = -ENOTTY; /* Bad command */
+ break;
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: skel_initialize
+ *
+ * Description:
+ * Create an initialize MTD device instance. 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).
+ *
+ ****************************************************************************/
+
+void skel_initialize(void)
+{
+ /* Perform initialization as necessary */
+
+ /* Return the implementation-specific state structure as the MTD device */
+
+ return ((FAR struct mtd_dev_s *)&g_skeldev;
+}
diff --git a/nuttx/include/nuttx/ioctl.h b/nuttx/include/nuttx/ioctl.h
index 670d75304..c1c3eafb0 100644
--- a/nuttx/include/nuttx/ioctl.h
+++ b/nuttx/include/nuttx/ioctl.h
@@ -97,7 +97,8 @@
#define _BIOCVALID(c) (_IOC_TYPE(c)==_BIOCBASE)
#define _BIOC(nr) _IOC(_BIOCBASE,nr)
-#define BIOC_XIPBASE _BIOC(0x0001) /* IN: None
+#define BIOC_XIPBASE _BIOC(0x0001) /* IN: Pointer to pointer to void in
+ * which to received the XIP base.
* OUT: If media is directly acccesible,
* return (void*) base address
* of device memory */
@@ -108,10 +109,12 @@
#define _MTDIOC(nr) _IOC(_MTDIOCBASE,nr)
#define MTDIOC_GEOMETRY _MTDIOC(0x0001) /* IN: Pointer to write-able struct
- * mtd_geometry_s (see mtd.h)
+ * mtd_geometry_s in which to receive
+ * receive geometry data (see mtd.h)
* OUT: Geometry structure is populated
* with data for the MTD */
-#define MTDIOC_XIPBASE _MTDIOC(0x0002) /* IN: None
+#define MTDIOC_XIPBASE _MTDIOC(0x0002) /* IN: Pointer to pointer to void in
+ * which to received the XIP base.
* OUT: If media is directly acccesible,
* return (void*) base address
* of device memory */
diff --git a/nuttx/include/nuttx/mtd.h b/nuttx/include/nuttx/mtd.h
new file mode 100644
index 000000000..435e9981b
--- /dev/null
+++ b/nuttx/include/nuttx/mtd.h
@@ -0,0 +1,128 @@
+/****************************************************************************
+ * include/nuttx/mtd.h
+ * Memory Technology Device (MTD) interface
+ *
+ * Copyright (C) 2007-2009 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.
+ *
+ ****************************************************************************/
+
+#ifndef __INCLUDE_NUTTX_MTD_H
+#define __INCLUDE_NUTTX_MTD_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Macros to hide implementation */
+
+#define MTD_ERASE(d,s,n) ((d)->erase ? (d)->erase(d,s,n) : (-ENOSYS))
+#define MTD_READ(d,s,n,b) ((d)->read ? (d)->read(d,s,n,b) : (-ENOSYS))
+#define MTD_WRITE(d,s,n,b) ((d)->write ? (d)->write(d,s,n,b) : (-ENOSYS))
+#define MTD_IOCTL(d,c,a) ((d)->ioctl ? (d)->ioctl(d,c,a) : (-ENOSYS))
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/* The following defines the geometry for the device. It treats the device
+ * 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.
+ */
+
+struct mtd_geometry_s
+{
+ uint16 blocksize; /* Size of one read/write block */
+ uint16 erasesize; /* Size of one erase blocks -- must be a multiple
+ * of blocksize. */
+ size_t neraseblocks; /* Number of erase blocks */
+};
+
+/* This structure defines the interface to a simple memory technology device.
+ * It will likely need to be extended in the future to support more complex
+ * devices.
+ */
+
+struct mtd_dev_s
+{
+ /* The following methods operate on the MTD: */
+
+ /* Erase the specified erase blocks */
+
+ int (*erase)(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks);
+
+ /* Read/write from the specified read/write blocks */
+
+ int (*read)(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR ubyte *buffer);
+ int (*write)(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR const ubyte *buffer);
+
+ /* Support other, less frequently used commands:
+ * - MTDIOC_GEOMETRY: Get MTD geometry
+ * - MTDIOC_XIPBASE: Convert block to physical address for eXecute-In-Place
+ * (see include/nuttx/ioctl.h)
+ */
+
+ int (*ioctl)(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg);
+};
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __INCLUDE_NUTTX_MTD_H */
diff --git a/nuttx/include/nuttx/spi.h b/nuttx/include/nuttx/spi.h
index 4f6c00f53..6630de158 100644
--- a/nuttx/include/nuttx/spi.h
+++ b/nuttx/include/nuttx/spi.h
@@ -102,7 +102,8 @@
*
****************************************************************************/
-#define SPI_SETMODE(d,m) ((d)->ops->setmode ? (d)->ops->setmode(d,m) : (void))
+#define SPI_SETMODE(d,m) \
+ do { if ((d)->ops->setmode) (d)->ops->setmode(d,m); } while (0)
/****************************************************************************
* Name: SPI_SETBITS
@@ -119,7 +120,8 @@
*
****************************************************************************/
-#define SPI_SETBITS(d,b) ((d)->ops->setbits ? (d)->ops->setbits(d,b) : (void))
+#define SPI_SETBITS(d,b) \
+ do { if ((d)->ops->setbits) (d)->ops->setmode(d,b); } while (0)
/****************************************************************************
* Name: SPI_STATUS