summaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-05-01 10:59:57 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-05-01 10:59:57 -0600
commit5b280602d79bbb1a0625016be023aa429d6fe898 (patch)
tree3e0960e407ea8021ed20ed0bcbde56e36a226c25 /nuttx/drivers
parent1a5060c28be4edffb32eabc2ad422254fcd72bb2 (diff)
downloadpx4-nuttx-5b280602d79bbb1a0625016be023aa429d6fe898.tar.gz
px4-nuttx-5b280602d79bbb1a0625016be023aa429d6fe898.tar.bz2
px4-nuttx-5b280602d79bbb1a0625016be023aa429d6fe898.zip
Add an optional byte-oriented write method to the MTD interface
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/mtd/Kconfig19
-rw-r--r--nuttx/drivers/mtd/at24xx.c8
-rw-r--r--nuttx/drivers/mtd/at25.c8
-rw-r--r--nuttx/drivers/mtd/at45db.c8
-rw-r--r--nuttx/drivers/mtd/m25px.c6
-rw-r--r--nuttx/drivers/mtd/mtd_partition.c6
-rw-r--r--nuttx/drivers/mtd/rammtd.c6
-rw-r--r--nuttx/drivers/mtd/ramtron.c6
-rw-r--r--nuttx/drivers/mtd/skeleton.c31
-rw-r--r--nuttx/drivers/mtd/sst25.c6
-rw-r--r--nuttx/drivers/mtd/sst39vf.c5
-rw-r--r--nuttx/drivers/mtd/w25.c6
12 files changed, 90 insertions, 25 deletions
diff --git a/nuttx/drivers/mtd/Kconfig b/nuttx/drivers/mtd/Kconfig
index 6755ffe7a..4e5e42549 100644
--- a/nuttx/drivers/mtd/Kconfig
+++ b/nuttx/drivers/mtd/Kconfig
@@ -3,6 +3,8 @@
# see misc/tools/kconfig-language.txt.
#
+comment "MTD Configuration"
+
config MTD_PARTITION
bool "Support MTD partitions"
default n
@@ -24,6 +26,17 @@ config MTD_PARTITION
managing the sub-region of flash beginning at 'offset' (in blocks)
and of size 'nblocks' on the device specified by 'mtd'.
+config MTD_BYTE_WRITE
+ bool "Byte write"
+ default n
+ ---help---
+ Some devices (such as the EON EN25F80) support writing an arbitrary
+ number of bytes to FLASH. This setting enables MTD interfaces to
+ support such writes. The SMART file system can take advantage of
+ this option if it is enabled.
+
+comment "MTD Device Drivers"
+
config RAMMTD
bool "RAM-based MTD driver"
default n
@@ -132,9 +145,9 @@ config MP25P_SUBSECTOR_ERASE
bool "Sub-Sector Erase"
default n
---help---
- Some devices (the EON EN25F80) support a smaller erase block size (4K vs 64K).
- This option enables support for sub-sector erase. The SMART file system can
- take advantage of this option if it is enabled.
+ Some devices (such as the EON EN25F80) support a smaller erase block
+ size (4K vs 64K). This option enables support for sub-sector erase.
+ The SMART file system can take advantage of this option if it is enabled.
config MP25P_BYTEWRITE
bool "Enable ByteWrite ioctl support"
diff --git a/nuttx/drivers/mtd/at24xx.c b/nuttx/drivers/mtd/at24xx.c
index d157a9c47..2eb7c9af0 100644
--- a/nuttx/drivers/mtd/at24xx.c
+++ b/nuttx/drivers/mtd/at24xx.c
@@ -10,7 +10,7 @@
*
* Derived from drivers/mtd/m25px.c
*
- * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -365,7 +365,7 @@ static int at24c_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
break;
case MTDIOC_BULKERASE:
- ret=at24c_eraseall(priv);
+ ret = at24c_eraseall(priv);
break;
case MTDIOC_XIPBASE:
@@ -413,6 +413,10 @@ FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev)
priv->pagesize = AT24XX_PAGESIZE;
priv->npages = AT24XX_NPAGES;
+ /* NOTE since the pre-allocated device structure lies in .bss, any
+ * unsupported methods should have been nullified.
+ */
+
priv->mtd.erase = at24c_erase;
priv->mtd.bread = at24c_bread;
priv->mtd.bwrite = at24c_bwrite;
diff --git a/nuttx/drivers/mtd/at25.c b/nuttx/drivers/mtd/at25.c
index c58b16122..6c4e183eb 100644
--- a/nuttx/drivers/mtd/at25.c
+++ b/nuttx/drivers/mtd/at25.c
@@ -2,7 +2,7 @@
* drivers/mtd/at25.c
* Driver for SPI-based AT25DF321 (32Mbit) flash.
*
- * Copyright (C) 2009-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Petteri Aimonen <jpa@nx.mail.kapsi.fi>
*
@@ -664,10 +664,12 @@ FAR struct mtd_dev_s *at25_initialize(FAR struct spi_dev_s *dev)
* to be extended to handle multiple FLASH parts on the same SPI bus.
*/
- priv = (FAR struct at25_dev_s *)kmalloc(sizeof(struct at25_dev_s));
+ priv = (FAR struct at25_dev_s *)kzalloc(sizeof(struct at25_dev_s));
if (priv)
{
- /* Initialize the allocated structure */
+ /* Initialize the allocated structure (unsupported methods were
+ * nullified by kzalloc).
+ */
priv->mtd.erase = at25_erase;
priv->mtd.bread = at25_bread;
diff --git a/nuttx/drivers/mtd/at45db.c b/nuttx/drivers/mtd/at45db.c
index f3c0c72c1..fbdc9090a 100644
--- a/nuttx/drivers/mtd/at45db.c
+++ b/nuttx/drivers/mtd/at45db.c
@@ -2,7 +2,7 @@
* drivers/mtd/at45db.c
* Driver for SPI-based AT45DB161D (16Mbit)
*
- * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010-2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -827,10 +827,12 @@ FAR struct mtd_dev_s *at45db_initialize(FAR struct spi_dev_s *spi)
* to be extended to handle multiple FLASH parts on the same SPI bus.
*/
- priv = (FAR struct at45db_dev_s *)kmalloc(sizeof(struct at45db_dev_s));
+ priv = (FAR struct at45db_dev_s *)kzalloc(sizeof(struct at45db_dev_s));
if (priv)
{
- /* Initialize the allocated structure */
+ /* Initialize the allocated structure. (unsupported methods were
+ * nullified by kzalloc).
+ */
priv->mtd.erase = at45db_erase;
priv->mtd.bread = at45db_bread;
diff --git a/nuttx/drivers/mtd/m25px.c b/nuttx/drivers/mtd/m25px.c
index ad0f536c2..8cd4ea134 100644
--- a/nuttx/drivers/mtd/m25px.c
+++ b/nuttx/drivers/mtd/m25px.c
@@ -995,10 +995,12 @@ FAR struct mtd_dev_s *m25p_initialize(FAR struct spi_dev_s *dev)
* to be extended to handle multiple FLASH parts on the same SPI bus.
*/
- priv = (FAR struct m25p_dev_s *)kmalloc(sizeof(struct m25p_dev_s));
+ priv = (FAR struct m25p_dev_s *)kzalloc(sizeof(struct m25p_dev_s));
if (priv)
{
- /* Initialize the allocated structure */
+ /* Initialize the allocated structure. (unsupported methods were
+ * nullified by kzalloc).
+ */
priv->mtd.erase = m25p_erase;
priv->mtd.bread = m25p_bread;
diff --git a/nuttx/drivers/mtd/mtd_partition.c b/nuttx/drivers/mtd/mtd_partition.c
index aba6c6930..1dc0f79ae 100644
--- a/nuttx/drivers/mtd/mtd_partition.c
+++ b/nuttx/drivers/mtd/mtd_partition.c
@@ -395,14 +395,16 @@ FAR struct mtd_dev_s *mtd_partition(FAR struct mtd_dev_s *mtd, off_t firstblock,
/* Allocate a partition device structure */
- part = (FAR struct mtd_partition_s *)malloc(sizeof(struct mtd_partition_s));
+ part = (FAR struct mtd_partition_s *)kzalloc(sizeof(struct mtd_partition_s));
if (!part)
{
fdbg("ERROR: Failed to allocate memory for the partition device\n");
return NULL;
}
- /* Initialize the partition device structure */
+ /* Initialize the partition device structure. (unsupported methods were
+ * nullified by kzalloc).
+ */
part->child.erase = part_erase;
part->child.bread = part_bread;
diff --git a/nuttx/drivers/mtd/rammtd.c b/nuttx/drivers/mtd/rammtd.c
index cbfe83e45..461cd7d99 100644
--- a/nuttx/drivers/mtd/rammtd.c
+++ b/nuttx/drivers/mtd/rammtd.c
@@ -429,7 +429,7 @@ FAR struct mtd_dev_s *rammtd_initialize(FAR uint8_t *start, size_t size)
/* Create an instance of the RAM MTD device state structure */
- priv = (FAR struct ram_dev_s *)kmalloc(sizeof(struct ram_dev_s));
+ priv = (FAR struct ram_dev_s *)kzalloc(sizeof(struct ram_dev_s));
if (!priv)
{
fdbg("Failed to allocate the RAM MTD state structure\n");
@@ -445,7 +445,9 @@ FAR struct mtd_dev_s *rammtd_initialize(FAR uint8_t *start, size_t size)
return NULL;
}
- /* Perform initialization as necessary */
+ /* Perform initialization as necessary. (unsupported methods were
+ * nullified by kzalloc).
+ */
priv->mtd.erase = ram_erase;
priv->mtd.bread = ram_bread;
diff --git a/nuttx/drivers/mtd/ramtron.c b/nuttx/drivers/mtd/ramtron.c
index 71e076934..44bc46c2e 100644
--- a/nuttx/drivers/mtd/ramtron.c
+++ b/nuttx/drivers/mtd/ramtron.c
@@ -660,10 +660,12 @@ FAR struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev)
* to be extended to handle multiple FLASH parts on the same SPI bus.
*/
- priv = (FAR struct ramtron_dev_s *)kmalloc(sizeof(struct ramtron_dev_s));
+ priv = (FAR struct ramtron_dev_s *)kzalloc(sizeof(struct ramtron_dev_s));
if (priv)
{
- /* Initialize the allocated structure */
+ /* Initialize the allocated structure. (unsupported methods were
+ * nullified by kzalloc).
+ */
priv->mtd.erase = ramtron_erase;
priv->mtd.bread = ramtron_bread;
diff --git a/nuttx/drivers/mtd/skeleton.c b/nuttx/drivers/mtd/skeleton.c
index d3b0937bf..fe550f55e 100644
--- a/nuttx/drivers/mtd/skeleton.c
+++ b/nuttx/drivers/mtd/skeleton.c
@@ -79,6 +79,10 @@ static ssize_t skel_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t n
FAR const uint8_t *buf);
static ssize_t skel_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
FAR uint8_t *buffer);
+#ifdef CONFIG_MTD_BYTE_WRITE
+static ssize_t skel_write(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
+ FAR const uint8_t *buffer);
+#endif
static int skel_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg);
/****************************************************************************
@@ -88,7 +92,15 @@ 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_rbead, skel_bwrite, skel_read, skel_ioctl },
+ { skel_erase,
+ skel_rbead,
+ skel_bwrite,
+ skel_read,
+#ifdef CONFIG_MTD_BYTE_WRITE
+ skel_write,
+#endif
+ skel_ioctl
+ },
/* Initialization of any other implementation specific data goes here */
};
@@ -203,6 +215,23 @@ static ssize_t skel_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
}
/****************************************************************************
+ * Name: skel_write
+ *
+ * Description:
+ * Some FLASH parts have the ability to write an arbitrary number of
+ * bytes to an arbitrary offset on the device.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_MTD_BYTE_WRITE
+static ssize_t skel_write(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
+ FAR const uint8_t *buffer)
+{
+ return -ENOSYS;
+}
+#endif
+
+/****************************************************************************
* Name: skel_ioctl
****************************************************************************/
diff --git a/nuttx/drivers/mtd/sst25.c b/nuttx/drivers/mtd/sst25.c
index 66d201add..0f58c4ae2 100644
--- a/nuttx/drivers/mtd/sst25.c
+++ b/nuttx/drivers/mtd/sst25.c
@@ -2,7 +2,7 @@
* drivers/mtd/sst25.c
* Driver for SPI-based SST25 FLASH.
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -1195,7 +1195,9 @@ FAR struct mtd_dev_s *sst25_initialize(FAR struct spi_dev_s *dev)
priv = (FAR struct sst25_dev_s *)kzalloc(sizeof(struct sst25_dev_s));
if (priv)
{
- /* Initialize the allocated structure */
+ /* Initialize the allocated structure. (unsupported methods were
+ * nullified by kzalloc).
+ */
priv->mtd.erase = sst25_erase;
priv->mtd.bread = sst25_bread;
diff --git a/nuttx/drivers/mtd/sst39vf.c b/nuttx/drivers/mtd/sst39vf.c
index ac2e88b3e..7c0bac786 100644
--- a/nuttx/drivers/mtd/sst39vf.c
+++ b/nuttx/drivers/mtd/sst39vf.c
@@ -201,7 +201,10 @@ static struct sst39vf_dev_s g_sst39vf =
sst39vf_bread, /* bread method */
sst39vf_bwrite, /* bwrte method */
sst39vf_read, /* read method */
- sst39vf_ioctl /* write method */
+#ifdef CONFIG_MTD_BYTE_WRITE
+ NULL, /* write method */
+#endif
+ sst39vf_ioctl /* ioctl method */
},
NULL /* Chip */
};
diff --git a/nuttx/drivers/mtd/w25.c b/nuttx/drivers/mtd/w25.c
index bd6680fdf..065e04528 100644
--- a/nuttx/drivers/mtd/w25.c
+++ b/nuttx/drivers/mtd/w25.c
@@ -2,7 +2,7 @@
* drivers/mtd/w25.c
* Driver for SPI-based W25x16, x32, and x64 and W25q16, q32, q64, and q128 FLASH
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -1124,7 +1124,9 @@ FAR struct mtd_dev_s *w25_initialize(FAR struct spi_dev_s *spi)
priv = (FAR struct w25_dev_s *)kzalloc(sizeof(struct w25_dev_s));
if (priv)
{
- /* Initialize the allocated structure */
+ /* Initialize the allocated structure (unsupported methods were
+ * nullified by kzalloc).
+ */
priv->mtd.erase = w25_erase;
priv->mtd.bread = w25_bread;