summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-01-17 16:33:09 +0100
committerAnton Babushkin <anton.babushkin@me.com>2014-01-17 16:33:09 +0100
commitb0c2c7edc9087997fd0a5eb0dd5487bdf4f2a030 (patch)
tree1d980e843b645b0dfb7ba866790069c603ce0527
parent16c4e7f4e1987ef5da6be8a21a999e7dd7de1a6e (diff)
parentbfbccf65227026c961c22612f84555dcd48588ac (diff)
downloadpx4-nuttx-b0c2c7edc9087997fd0a5eb0dd5487bdf4f2a030.tar.gz
px4-nuttx-b0c2c7edc9087997fd0a5eb0dd5487bdf4f2a030.tar.bz2
px4-nuttx-b0c2c7edc9087997fd0a5eb0dd5487bdf4f2a030.zip
Merge branch 'master' into env_expand
-rw-r--r--nuttx/drivers/mtd/at24xx.c15
-rw-r--r--nuttx/drivers/mtd/ramtron.c128
-rw-r--r--nuttx/include/nuttx/fs/ioctl.h2
3 files changed, 98 insertions, 47 deletions
diff --git a/nuttx/drivers/mtd/at24xx.c b/nuttx/drivers/mtd/at24xx.c
index 2eb7c9af0..8d89f9bd2 100644
--- a/nuttx/drivers/mtd/at24xx.c
+++ b/nuttx/drivers/mtd/at24xx.c
@@ -230,12 +230,17 @@ static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock,
uint8_t buf[2];
buf[1] = offset & 0xff;
buf[0] = (offset >> 8) & 0xff;
+ uint8_t tries = 100;
- while (I2C_WRITE(priv->dev, buf, 2) < 0)
+ while (I2C_WRITE(priv->dev, buf, 2) < 0 && tries-- > 0)
{
fvdbg("wait\n");
usleep(1000);
}
+ if (tries == 0) {
+ fdbg("timed out reading at offset %u\n", (unsigned)offset);
+ return 0;
+ }
I2C_READ(priv->dev, buffer, priv->pagesize);
startblock++;
@@ -286,11 +291,17 @@ static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t
while (blocksleft-- > 0)
{
uint16_t offset = startblock * priv->pagesize;
- while (I2C_WRITE(priv->dev, (uint8_t *)&offset, 2) < 0)
+ uint8_t tries = 100;
+
+ while (I2C_WRITE(priv->dev, (uint8_t *)&offset, 2) < 0 && tries-- > 0)
{
fvdbg("wait\n");
usleep(1000);
}
+ if (tries == 0) {
+ fdbg("timed out writing at offset %u\n", (unsigned)offset);
+ return 0;
+ }
buf[1] = offset & 0xff;
buf[0] = (offset >> 8) & 0xff;
diff --git a/nuttx/drivers/mtd/ramtron.c b/nuttx/drivers/mtd/ramtron.c
index 44bc46c2e..b53c7829b 100644
--- a/nuttx/drivers/mtd/ramtron.c
+++ b/nuttx/drivers/mtd/ramtron.c
@@ -1,6 +1,6 @@
/************************************************************************************
* drivers/mtd/ramtron.c
- * Driver for SPI-based RAMTRON NVRAM Devices FM25V10 and others (not tested)
+ * Driver for SPI-based RAMTRON NVRAM Devices FM25V10 and others
*
* Copyright (C) 2011 Uros Platise. All rights reserved.
* Copyright (C) 2009-2010, 2012-2013 Gregory Nutt. All rights reserved.
@@ -40,13 +40,6 @@
* - additional non-jedec standard device: FM25H20
* must be enabled with the CONFIG_RAMTRON_FRAM_NON_JEDEC=y
*
- * NOTE:
- * - frequency is fixed to desired max by RAMTRON_INIT_CLK_MAX
- * if new devices with different speed arrive, then SETFREQUENCY()
- * needs to handle freq changes and INIT_CLK_MAX must be reduced
- * to fit all devices. Note that STM32_SPI driver is prone to
- * too high freq. parameters and limit it within physical constraints.
- *
* TODO:
* - add support for sleep
* - add support for faster read FSTRD command
@@ -146,6 +139,7 @@ struct ramtron_dev_s
uint8_t pageshift;
uint16_t nsectors;
uint32_t npages;
+ uint32_t speed; // overridable via ioctl
const struct ramtron_parts_s *part; /* part instance */
};
@@ -154,10 +148,12 @@ struct ramtron_dev_s
************************************************************************************/
/* Defines the initial speed compatible with all devices. In case of RAMTRON
- * the defined devices within the part list have all the same speed.
+ * the defined devices within the part list have all the same
+ * speed.
*/
-#define RAMTRON_INIT_CLK_MAX 40000000UL
+#define RAMTRON_CLK_MAX 40*1000*1000UL
+#define RAMTRON_INIT_CLK_DEFAULT 11*1000*1000UL
static struct ramtron_parts_s ramtron_parts[] =
{
@@ -244,12 +240,12 @@ static struct ramtron_parts_s ramtron_parts[] =
/* Helpers */
-static void ramtron_lock(FAR struct spi_dev_s *dev);
+static void ramtron_lock(FAR struct ramtron_dev_s *priv);
static inline void ramtron_unlock(FAR struct spi_dev_s *dev);
static inline int ramtron_readid(struct ramtron_dev_s *priv);
-static void ramtron_waitwritecomplete(struct ramtron_dev_s *priv);
+static int ramtron_waitwritecomplete(struct ramtron_dev_s *priv);
static void ramtron_writeenable(struct ramtron_dev_s *priv);
-static inline void ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8_t *buffer,
+static inline int ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8_t *buffer,
off_t offset);
/* MTD driver methods */
@@ -275,7 +271,7 @@ static int ramtron_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg);
* Name: ramtron_lock
************************************************************************************/
-static void ramtron_lock(FAR struct spi_dev_s *dev)
+static void ramtron_lock(FAR struct ramtron_dev_s *priv)
{
/* On SPI busses where there are multiple devices, it will be necessary to
* lock SPI to have exclusive access to the busses for a sequence of
@@ -285,7 +281,7 @@ static void ramtron_lock(FAR struct spi_dev_s *dev)
* the SPI buss. We will retain that exclusive access until the bus is unlocked.
*/
- (void)SPI_LOCK(dev, true);
+ (void)SPI_LOCK(priv->dev, true);
/* After locking the SPI bus, the we also need call the setfrequency, setbits, and
* setmode methods to make sure that the SPI is properly configured for the device.
@@ -293,10 +289,10 @@ static void ramtron_lock(FAR struct spi_dev_s *dev)
* state.
*/
- SPI_SETMODE(dev, SPIDEV_MODE3);
- SPI_SETBITS(dev, 8);
-
- (void)SPI_SETFREQUENCY(dev, RAMTRON_INIT_CLK_MAX);
+ SPI_SETMODE(priv->dev, SPIDEV_MODE3);
+ SPI_SETBITS(priv->dev, 8);
+
+ (void)SPI_SETFREQUENCY(priv->dev, priv->speed);
}
/************************************************************************************
@@ -321,7 +317,7 @@ static inline int ramtron_readid(struct ramtron_dev_s *priv)
/* Lock the SPI bus, configure the bus, and select this FLASH part. */
- ramtron_lock(priv->dev);
+ ramtron_lock(priv);
SPI_SELECT(priv->dev, SPIDEV_FLASH, true);
/* Send the "Read ID (RDID)" command and read the first three ID bytes */
@@ -356,6 +352,7 @@ static inline int ramtron_readid(struct ramtron_dev_s *priv)
priv->nsectors = priv->part->size / (1 << RAMTRON_EMULATE_SECTOR_SHIFT);
priv->pageshift = RAMTRON_EMULATE_PAGE_SHIFT;
priv->npages = priv->part->size / (1 << RAMTRON_EMULATE_PAGE_SHIFT);
+ priv->speed = priv->part->speed;
return OK;
}
@@ -367,7 +364,7 @@ static inline int ramtron_readid(struct ramtron_dev_s *priv)
* Name: ramtron_waitwritecomplete
************************************************************************************/
-static void ramtron_waitwritecomplete(struct ramtron_dev_s *priv)
+static int ramtron_waitwritecomplete(struct ramtron_dev_s *priv)
{
uint8_t status;
@@ -379,20 +376,35 @@ static void ramtron_waitwritecomplete(struct ramtron_dev_s *priv)
(void)SPI_SEND(priv->dev, RAMTRON_RDSR);
- /* Loop as long as the memory is busy with a write cycle */
+ /* Loop as long as the memory is busy with a write cycle,
+ * but limit the cycles.
+ *
+ * RAMTRON FRAM is never busy per spec compared to flash,
+ * and so anything exceeding the default timeout number
+ * is highly suspicious.
+ */
+ unsigned int tries = 100; // XXX should be CONFIG_MTD_RAMTRON_WRITEWAIT_COUNT
do
{
/* Send a dummy byte to generate the clock needed to shift out the status */
status = SPI_SEND(priv->dev, RAMTRON_DUMMY);
+ tries--;
}
- while ((status & RAMTRON_SR_WIP) != 0);
+ while ((status & RAMTRON_SR_WIP) != 0 && tries > 0);
/* Deselect the FLASH */
SPI_SELECT(priv->dev, SPIDEV_FLASH, false);
fvdbg("Complete\n");
+
+ if (tries == 0) {
+ fdbg("timeout waiting for write completion\n");
+ return -EAGAIN;
+ }
+
+ return OK;
}
/************************************************************************************
@@ -436,21 +448,13 @@ static inline void ramtron_sendaddr(const struct ramtron_dev_s *priv, uint32_t a
* Name: ramtron_pagewrite
************************************************************************************/
-static inline void ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8_t *buffer,
+static inline int ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8_t *buffer,
off_t page)
{
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.
- */
-
- ramtron_waitwritecomplete(priv);
-
/* Enable the write access to the FLASH */
ramtron_writeenable(priv);
@@ -475,6 +479,16 @@ static inline void ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8
SPI_SELECT(priv->dev, SPIDEV_FLASH, false);
fvdbg("Written\n");
+
+ // we wait for write completion now so we can report any errors to
+ // the caller. Otherwise the caller has no way of knowing if the
+ // data is on stable storage
+ int ret = ramtron_waitwritecomplete(priv);
+
+ if (ret)
+ return ret;
+
+ return OK;
}
/************************************************************************************
@@ -525,15 +539,20 @@ static ssize_t ramtron_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_
/* Lock the SPI bus and write each page to FLASH */
- ramtron_lock(priv->dev);
+ ramtron_lock(priv);
+
while (blocksleft-- > 0)
{
- ramtron_pagewrite(priv, buffer, startblock);
+ if (ramtron_pagewrite(priv, buffer, startblock)) {
+ nblocks = 0;
+ goto error;
+ }
startblock++;
}
- ramtron_unlock(priv->dev);
- return nblocks;
+ error:
+ ramtron_unlock(priv->dev);
+ return nblocks;
}
/************************************************************************************
@@ -547,17 +566,9 @@ static ssize_t ramtron_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyt
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.
- */
-
- ramtron_waitwritecomplete(priv);
-
/* Lock the SPI bus and select this FLASH part */
- ramtron_lock(priv->dev);
+ ramtron_lock(priv);
SPI_SELECT(priv->dev, SPIDEV_FLASH, true);
/* Send "Read from Memory " instruction */
@@ -572,6 +583,20 @@ static ssize_t ramtron_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyt
SPI_RECVBLOCK(priv->dev, buffer, nbytes);
+ // read the status register. This isn't strictly needed, but it
+ // gives us a chance to detect if SPI transactions are operating
+ // correctly, which allows us to catch complete device failures in
+ // the read path. We expect the status register to just have the
+ // write enable bit set to the write enable state
+ (void)SPI_SEND(priv->dev, RAMTRON_RDSR);
+ uint8_t status = SPI_SEND(priv->dev, RAMTRON_DUMMY);
+ if ((status & ~RAMTRON_SR_SRWD) == 0) {
+ fdbg("read status failed - got 0x%02x\n", (unsigned)status);
+ SPI_SELECT(priv->dev, SPIDEV_FLASH, false);
+ ramtron_unlock(priv->dev);
+ return -EIO;
+ }
+
/* Deselect the FLASH and unlock the SPI bus */
SPI_SELECT(priv->dev, SPIDEV_FLASH, false);
@@ -622,6 +647,18 @@ static int ramtron_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
fvdbg("BULDERASE: Makes no sense in ramtron. Let's confirm operation as OK\n");
ret = OK;
break;
+
+ case MTDIOC_SETSPEED:
+ {
+ if ((unsigned long)arg > 0 && (unsigned long)arg <= RAMTRON_CLK_MAX) {
+ priv->speed = (unsigned long)arg;
+ fvdbg("set bus speed to %lu\n", (unsigned long)priv->speed);
+ } else {
+ ret = -EINVAL; /* Bad argument */
+ fvdbg("inval arg");
+ }
+ break;
+ }
case MTDIOC_XIPBASE:
default:
@@ -673,6 +710,7 @@ FAR struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev)
priv->mtd.read = ramtron_read;
priv->mtd.ioctl = ramtron_ioctl;
priv->dev = dev;
+ priv->speed = RAMTRON_INIT_CLK_DEFAULT;
/* Deselect the FLASH */
diff --git a/nuttx/include/nuttx/fs/ioctl.h b/nuttx/include/nuttx/fs/ioctl.h
index e36083253..09a6c2e1a 100644
--- a/nuttx/include/nuttx/fs/ioctl.h
+++ b/nuttx/include/nuttx/fs/ioctl.h
@@ -204,6 +204,8 @@
* of device memory */
#define MTDIOC_BULKERASE _MTDIOC(0x0003) /* IN: None
* OUT: None */
+#define MTDIOC_SETSPEED _MTDIOC(0x0004) /* IN: (unsigned long) desired bus speed
+ * OUT: None */
/* NuttX ARP driver ioctl definitions (see netinet/arp.h) *******************/