summaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-10-18 20:58:04 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-10-18 20:58:04 +0000
commitdbaa783ef42ef49c436a116436a17e7b34553ccb (patch)
tree079f11132686f61353cc96d95ac991bf590e461e /nuttx/drivers
parent256fbb5e5d5dac428e58adeb0272567c69a5e7d9 (diff)
downloadpx4-nuttx-dbaa783ef42ef49c436a116436a17e7b34553ccb.tar.gz
px4-nuttx-dbaa783ef42ef49c436a116436a17e7b34553ccb.tar.bz2
px4-nuttx-dbaa783ef42ef49c436a116436a17e7b34553ccb.zip
Add bulk erase IOCTL; add byte read method
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2158 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/mtd/m25px.c314
-rw-r--r--nuttx/drivers/mtd/skeleton.c63
2 files changed, 257 insertions, 120 deletions
diff --git a/nuttx/drivers/mtd/m25px.c b/nuttx/drivers/mtd/m25px.c
index 1ab71f877..c94c72fa0 100644
--- a/nuttx/drivers/mtd/m25px.c
+++ b/nuttx/drivers/mtd/m25px.c
@@ -43,6 +43,7 @@
#include <sys/types.h>
#include <stdlib.h>
#include <errno.h>
+#include <debug.h>
#include <nuttx/ioctl.h>
#include <nuttx/spi.h>
@@ -111,7 +112,7 @@
# 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
+#define M25P_DUMMY 0xa5
/************************************************************************************
* Private Types
@@ -139,19 +140,22 @@ struct m25p_dev_s
/* 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 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 offset);
+static inline int m25p_bulkerase(struct m25p_dev_s *priv);
static inline void m25p_pagewrite(struct m25p_dev_s *priv, FAR const ubyte *buffer,
- off_t address);
+ off_t offset);
/* 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_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR ubyte *buf);
+static int m25p_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR const ubyte *buf);
+static int m25p_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
+ FAR ubyte *buffer);
static int m25p_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg);
/************************************************************************************
@@ -172,21 +176,26 @@ static inline int m25p_readid(struct m25p_dev_s *priv)
uint16 memory;
uint16 capacity;
+ fvdbg("priv: %p\n", 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 "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 */
+
+ fvdbg("manufacturer: %02x memory: %02x capacity: %02x\n",
+ manufacturer, memory, capacity);
+
+ /* Deselect the FLASH */
SPI_SELECT(priv->dev, SPIDEV_FLASH, FALSE);
@@ -215,132 +224,177 @@ static inline int m25p_readid(struct m25p_dev_s *priv)
return OK;
}
}
-
- return -ENODEV;
+
+ return -ENODEV;
}
/************************************************************************************
* Name: m25p_waitwritecomplete
************************************************************************************/
-static void m25p_waitwritecomplete(struct m25p_dev_s *priv)
+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
- {
+
+ do
+ {
/* Send a dummy byte to generate the clock needed to shift out the status */
- status = SPI_SEND(priv->dev, M25P_DUMMY);
+ status = SPI_SEND(priv->dev, M25P_DUMMY);
}
- while ((status & M25P_SR_WIP) != 0);
-
- /* Deselect the FLASH */
+ while ((status & M25P_SR_WIP) != 0);
+
+ /* Deselect the FLASH */
SPI_SELECT(priv->dev, SPIDEV_FLASH, FALSE);
-}
+ fvdbg("Complete\n");
+}
/************************************************************************************
* Name: m25p_writeenable
************************************************************************************/
-static void m25p_writeenable(struct m25p_dev_s *priv)
-{
+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 */
+
+ /* Send "Write Enable (WREN)" command */
(void)SPI_SEND(priv->dev, M25P_WREN);
-
- /* Deselect the FLASH */
+
+ /* Deselect the FLASH */
SPI_SELECT(priv->dev, SPIDEV_FLASH, FALSE);
+ fvdbg("Enabled\n");
}
/************************************************************************************
* Name: m25p_sectorerase
************************************************************************************/
-static inline void m25p_sectorerase(struct m25p_dev_s *priv, off_t sector)
+static inline void m25p_sectorerase(struct m25p_dev_s *priv, off_t sector)
{
- off_t address = sector << priv->sectorshift;
-
+ off_t offset = sector << priv->sectorshift;
+
+ fvdbg("sector: %08lx\n", (long)sector);
+
/* 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);
-
+
+ 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
+ /* Send the sector offset 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);
+ (void)SPI_SEND(priv->dev, (offset >> 16) & 0xff);
+ (void)SPI_SEND(priv->dev, (offset >> 8) & 0xff);
+ (void)SPI_SEND(priv->dev, offset & 0xff);
- /* Deselect the FLASH */
+ /* Deselect the FLASH */
SPI_SELECT(priv->dev, SPIDEV_FLASH, FALSE);
-}
+ fvdbg("Erased\n");
+}
+
+/************************************************************************************
+ * Name: m25p_bulkerase
+ ************************************************************************************/
+
+static inline int m25p_bulkerase(struct m25p_dev_s *priv)
+{
+ fvdbg("priv: %p\n", priv);
+
+ /* 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 "Bulk Erase (BE)" instruction */
+
+ (void)SPI_SEND(priv->dev, M25P_BE);
+
+ /* Deselect the FLASH */
+
+ SPI_SELECT(priv->dev, SPIDEV_FLASH, FALSE);
+ fvdbg("Return: OK\n");
+ return OK;
+}
/************************************************************************************
* Name: m25p_pagewrite
************************************************************************************/
static inline void m25p_pagewrite(struct m25p_dev_s *priv, FAR const ubyte *buffer,
- off_t page)
+ off_t page)
{
- off_t address = page << priv->pageshift;
-
+ off_t offset = page << priv->pageshift;
+
+ fvdbg("page: %08lx offset: %08lx\n", (long)page, (long)offset);
+
/* 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);
-
+
+ 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.
@@ -348,24 +402,25 @@ static inline void m25p_pagewrite(struct m25p_dev_s *priv, FAR const ubyte *buff
SPI_SELECT(priv->dev, SPIDEV_FLASH, TRUE);
- /* Send "Page Program (PP)" command */
+ /* Send "Page Program (PP)" command */
(void)SPI_SEND(priv->dev, M25P_PP);
- /* Send the page address high byte first. */
+ /* Send the page offset 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);
+ (void)SPI_SEND(priv->dev, (offset >> 16) & 0xff);
+ (void)SPI_SEND(priv->dev, (offset >> 8) & 0xff);
+ (void)SPI_SEND(priv->dev, offset & 0xff);
/* Then write the specified number of bytes */
SPI_SNDBLOCK(priv->dev, buffer, 1 << priv->pageshift);
-
- /* Deselect the FLASH: Chip Select high */
+
+ /* Deselect the FLASH: Chip Select high */
SPI_SELECT(priv->dev, SPIDEV_FLASH, FALSE);
-}
+ fvdbg("Written\n");
+}
/************************************************************************************
* Name: m25p_erase
@@ -376,6 +431,8 @@ static int m25p_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblock
FAR struct m25p_dev_s *priv = (FAR struct m25p_dev_s *)dev;
size_t blocksleft = nblocks;
+ fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
+
while (blocksleft-- > 0)
{
m25p_sectorerase(priv, startblock);
@@ -386,25 +443,67 @@ static int m25p_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblock
}
/************************************************************************************
+ * Name: m25p_bread
+ ************************************************************************************/
+
+static ssize_t m25p_bread(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 nbytes;
+
+ fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
+
+ /* On this device, we can handle the block read just like the byte-oriented read */
+
+ nbytes = m25p_read(dev, startblock << priv->pageshift, nblocks << priv->pageshift, buffer);
+ if (nbytes > 0)
+ {
+ return nbytes >> priv->pageshift;
+ }
+ return nbytes;
+}
+
+/************************************************************************************
+ * Name: m25p_bwrite
+ ************************************************************************************/
+
+static ssize_t m25p_bwrite(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;
+
+ fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
+
+ /* Write each page to FLASH */
+
+ while (blocksleft-- > 0)
+ {
+ m25p_pagewrite(priv, buffer, startblock);
+ startblock++;
+ }
+
+ return nblocks;
+}
+
+/************************************************************************************
* Name: m25p_read
************************************************************************************/
-static int m25p_read(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
- FAR ubyte *buffer)
+static ssize_t m25p_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
+ 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;
-
+ fvdbg("offset: %08lx nbytes: %d\n", (long)offset, (int)nbytes);
+
/* 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
@@ -413,46 +512,26 @@ static int m25p_read(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks
*/
SPI_SELECT(priv->dev, SPIDEV_FLASH, TRUE);
-
- /* Send "Read from Memory " instruction */
+
+ /* Send "Read from Memory " instruction */
(void)SPI_SEND(priv->dev, M25P_READ);
- /* Send the page address high byte first. */
+ /* Send the page offset 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);
+ (void)SPI_SEND(priv->dev, (offset >> 16) & 0xff);
+ (void)SPI_SEND(priv->dev, (offset >> 8) & 0xff);
+ (void)SPI_SEND(priv->dev, offset & 0xff);
/* Then read all of the requested bytes */
- SPI_RECVBLOCK(priv->dev, buffer, nblocks << priv->pageshift);
+ SPI_RECVBLOCK(priv->dev, buffer, nbytes);
- /* Deselect the FLASH */
+ /* 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;
+ fvdbg("return nbytes: %d\n", (int)nbytes);
+ return nbytes;
}
/************************************************************************************
@@ -464,6 +543,8 @@ 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 */
+ fvdbg("cmd: %d \n", cmd);
+
switch (cmd)
{
case MTDIOC_GEOMETRY:
@@ -484,16 +565,28 @@ static int m25p_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
geo->erasesize = (1 << priv->sectorshift);
geo->neraseblocks = priv->nsectors;
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 = m25p_bulkerase(priv);
+ }
+ break;
+
case MTDIOC_XIPBASE:
default:
ret = -ENOTTY; /* Bad command */
break;
}
+ fvdbg("return %d\n", ret);
return ret;
}
@@ -516,6 +609,8 @@ FAR struct mtd_dev_s *m25p_initialize(FAR struct spi_dev_s *dev)
FAR struct m25p_dev_s *priv;
int ret;
+ fvdbg("dev: %p\n", dev);
+
/* 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
@@ -528,11 +623,12 @@ FAR struct mtd_dev_s *m25p_initialize(FAR struct spi_dev_s *dev)
{
/* 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;
+ priv->mtd.erase = m25p_erase;
+ priv->mtd.bread = m25p_bread;
+ priv->mtd.bwrite = m25p_bwrite;
+ priv->mtd.read = m25p_read;
+ priv->mtd.ioctl = m25p_ioctl;
+ priv->dev = dev;
/* Deselect the FLASH */
@@ -551,6 +647,7 @@ FAR struct mtd_dev_s *m25p_initialize(FAR struct spi_dev_s *dev)
{
/* Unrecognized! Discard all of that work we just did and return NULL */
+ fdbg("Unrecognized\n");
free(priv);
priv = NULL;
}
@@ -558,5 +655,6 @@ FAR struct mtd_dev_s *m25p_initialize(FAR struct spi_dev_s *dev)
/* Return the implementation-specific state structure as the MTD device */
+ fvdbg("Return %p\n", priv);
return (FAR struct mtd_dev_s *)priv;
}
diff --git a/nuttx/drivers/mtd/skeleton.c b/nuttx/drivers/mtd/skeleton.c
index 84df9ffe0..78faa20b4 100644
--- a/nuttx/drivers/mtd/skeleton.c
+++ b/nuttx/drivers/mtd/skeleton.c
@@ -72,10 +72,12 @@ struct skel_dev_s
/* 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 ssize_t skel_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR ubyte *buf);
+static ssize_t skel_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR const ubyte *buf);
+static ssize_t skel_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
+ FAR ubyte *buffer);
static int skel_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg);
/****************************************************************************
@@ -84,7 +86,7 @@ static int skel_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg);
static struct skel_dev_s g_skeldev =
{
- { skel_erase, skel_read, skel_write, skel_ioctl },
+ { skel_erase, skel_rbead, skel_bwrite, skel_read, skel_ioctl },
/* Initialization of any other implemenation specific data goes here */
};
@@ -111,11 +113,11 @@ static int skel_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblock
}
/****************************************************************************
- * Name: skel_read
+ * Name: skel_bread
****************************************************************************/
-static int skel_read(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
- FAR ubyte *buf)
+static ssize_t skel_bread(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;
@@ -125,18 +127,18 @@ static int skel_read(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks
*/
/* Read the specified blocks into the provided user buffer and return status
- * (The positive, number of blocks actually read or a negated errno)
+ * (The positive, number of blocks actually read or a negated errno).
*/
return 0;
}
/****************************************************************************
- * Name: skel_write
+ * Name: skel_bwrite
****************************************************************************/
-static int skel_write(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
- FAR const ubyte *buf)
+static ssize_t skel_bwrite(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;
@@ -153,6 +155,35 @@ static int skel_write(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblock
}
/****************************************************************************
+ * Name: skel_read
+ ****************************************************************************/
+
+static ssize_t skel_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
+ FAR ubyte *buffer)
+{
+ FAR struct skel_dev_s *priv = (FAR struct skel_dev_s *)dev;
+
+ /* Some devices may support byte oriented read (optional). Byte-oriented
+ * writing is inherently block oriented on most MTD devices and is not supported.
+ * It is recommended that low-level drivers not support read() if it requires
+ * buffering -- let the higher level logic handle that. If the read method is
+ * not implemented, just set the method pointer to NULL in the struct mtd_dev_s
+ * instance.
+ */
+
+ /* 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_ioctl
****************************************************************************/
@@ -202,6 +233,14 @@ static int skel_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
}
break;
+ case MTDIOC_BULKERASE
+ {
+ /* Erase the entire device */
+
+ ret = OK;
+ }
+ break;
+
default:
ret = -ENOTTY; /* Bad command */
break;