summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-09-25 13:35:10 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-09-25 13:35:10 -0600
commitf1366e4b1285d10d0521a7d0679d19edfe5cfff6 (patch)
tree73a8a0ac7d0d74ed0f0dcef2eb2512d0fd7259dd
parentf999f325f9b9f9fdc09650855f55a848785be67c (diff)
downloadpx4-nuttx-f1366e4b1285d10d0521a7d0679d19edfe5cfff6.tar.gz
px4-nuttx-f1366e4b1285d10d0521a7d0679d19edfe5cfff6.tar.bz2
px4-nuttx-f1366e4b1285d10d0521a7d0679d19edfe5cfff6.zip
MTD read-ahear/write buffering layer seems functional
-rw-r--r--apps/examples/mtdrwb/mtdrwb_main.c74
-rw-r--r--nuttx/drivers/bch/bchdev_driver.c6
-rw-r--r--nuttx/drivers/mtd/ftl.c3
-rw-r--r--nuttx/drivers/mtd/mtd_rwbuffer.c4
-rw-r--r--nuttx/drivers/rwbuffer.c100
5 files changed, 89 insertions, 98 deletions
diff --git a/apps/examples/mtdrwb/mtdrwb_main.c b/apps/examples/mtdrwb/mtdrwb_main.c
index 2a71c05db..21cb91a0c 100644
--- a/apps/examples/mtdrwb/mtdrwb_main.c
+++ b/apps/examples/mtdrwb/mtdrwb_main.c
@@ -158,8 +158,6 @@ int mtdrwb_main(int argc, char *argv[])
ssize_t nbytes;
off_t nblocks;
off_t offset;
- off_t check;
- off_t sectoff;
off_t seekpos;
unsigned int blkpererase;
int fd;
@@ -280,7 +278,7 @@ int mtdrwb_main(int argc, char *argv[])
for (k = 0; k < geo.blocksize / sizeof(uint32_t); k++)
{
buffer[k] = offset;
- offset += 4;
+ offset += sizeof(uint32_t);
}
/* And write it using the character driver */
@@ -297,9 +295,9 @@ int mtdrwb_main(int argc, char *argv[])
close(fd);
- /* Open the MTD character driver for writing */
+ /* Open the MTD character driver for reading */
- fd = open("/dev/mtd0", O_RDWR);
+ fd = open("/dev/mtd0", O_RDONLY);
if (fd < 0)
{
message("ERROR: open /dev/mtd0 failed: %d\n", errno);
@@ -309,21 +307,16 @@ int mtdrwb_main(int argc, char *argv[])
/* Now verify the offset in every block */
- check = offset;
- sectoff = 0;
-
+ offset = 0;
for (j = 0; j < nblocks; j++)
{
-#if 0 /* Too much */
- message(" block=%u offset=%lu\n", j, (unsigned long) check);
-#endif
/* Seek to the next read position */
- seekpos = lseek(fd, sectoff, SEEK_SET);
- if (seekpos != sectoff)
+ seekpos = lseek(fd, offset, SEEK_SET);
+ if (seekpos != offset)
{
message("ERROR: lseek to offset %ld failed: %d\n",
- (unsigned long)sectoff, errno);
+ (unsigned long)offset, errno);
msgflush();
exit(10);
}
@@ -356,17 +349,17 @@ int mtdrwb_main(int argc, char *argv[])
* indication.
*/
- else if (nbytes == 0)
+ else if (nbytes == 0)
{
message("ERROR: Unexpected end of file on /dev/mtd0\n");
msgflush();
- exit(14);
+ exit(14);
}
- /* This is not expected at all */
+ /* This is not expected at all */
- else if (nbytes != geo.blocksize)
- {
+ else if (nbytes != geo.blocksize)
+ {
message("ERROR: Short read from /dev/mtd0 failed: %lu\n",
(unsigned long)nbytes);
msgflush();
@@ -377,53 +370,16 @@ int mtdrwb_main(int argc, char *argv[])
for (k = 0; k < geo.blocksize / sizeof(uint32_t); k++)
{
- if (buffer[k] != check)
+ if (buffer[k] != offset)
{
message("ERROR: Bad offset %lu, expected %lu\n",
- (long)buffer[k], (long)check);
+ (long)buffer[k], (long)offset);
msgflush();
exit(16);
}
- /* Invert the value to indicate that we have verified
- * this value.
- */
-
- buffer[k] = ~check;
- check += sizeof(uint32_t);
+ offset += sizeof(uint32_t);
}
-
- /* Seek to the next write position */
-
- seekpos = lseek(fd, sectoff, SEEK_SET);
- if (seekpos != sectoff)
- {
- message("ERROR: lseek to offset %ld failed: %d\n",
- (unsigned long)sectoff, errno);
- msgflush();
- exit(17);
- }
-
- /* Now write the block back to FLASH with the modified value */
-
- nbytes = write(fd, buffer, geo.blocksize);
- if (nbytes < 0)
- {
- message("ERROR: write to /dev/mtd0 failed: %d\n", errno);
- msgflush();
- exit(18);
- }
- else if (nbytes != geo.blocksize)
- {
- message("ERROR: Unexpected write size to /dev/mtd0 : %ld\n",
- (unsigned long)nbytes);
- msgflush();
- exit(19);
- }
-
- /* Get the offset to the next block */
-
- sectoff += geo.blocksize;
}
/* Try reading one more time. We should get the end of file */
diff --git a/nuttx/drivers/bch/bchdev_driver.c b/nuttx/drivers/bch/bchdev_driver.c
index 6db09674d..b45170652 100644
--- a/nuttx/drivers/bch/bchdev_driver.c
+++ b/nuttx/drivers/bch/bchdev_driver.c
@@ -124,8 +124,8 @@ static int bch_open(FAR struct file *filep)
{
bch->refs++;
}
- bchlib_semgive(bch);
+ bchlib_semgive(bch);
return OK;
}
@@ -162,8 +162,8 @@ static int bch_close(FAR struct file *filep)
{
bch->refs--;
}
- bchlib_semgive(bch);
+ bchlib_semgive(bch);
return ret;
}
@@ -212,6 +212,7 @@ static ssize_t bch_write(FAR struct file *filep, FAR const char *buffer, size_t
{
filep->f_pos += len;
}
+
bchlib_semgive(bch);
}
@@ -248,6 +249,7 @@ static int bch_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
bch->refs++;
*bchr = bch;
}
+
bchlib_semgive(bch);
}
#if defined(CONFIG_BCH_ENCRYPTION)
diff --git a/nuttx/drivers/mtd/ftl.c b/nuttx/drivers/mtd/ftl.c
index 4e0204972..a0260a1f4 100644
--- a/nuttx/drivers/mtd/ftl.c
+++ b/nuttx/drivers/mtd/ftl.c
@@ -168,6 +168,7 @@ static ssize_t ftl_reload(FAR void *priv, FAR uint8_t *buffer,
fdbg("Read %d blocks starting at block %d failed: %d\n",
nblocks, startblock, nread);
}
+
return nread;
}
@@ -431,6 +432,7 @@ static int ftl_geometry(FAR struct inode *inode, struct geometry *geometry)
return OK;
}
+
return -EINVAL;
}
@@ -599,5 +601,6 @@ int ftl_initialize(int minor, FAR struct mtd_dev_s *mtd)
kmm_free(dev);
}
}
+
return ret;
}
diff --git a/nuttx/drivers/mtd/mtd_rwbuffer.c b/nuttx/drivers/mtd/mtd_rwbuffer.c
index 0cb3701af..4b9e39ea4 100644
--- a/nuttx/drivers/mtd/mtd_rwbuffer.c
+++ b/nuttx/drivers/mtd/mtd_rwbuffer.c
@@ -272,8 +272,8 @@ static int mtd_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
*/
geo->blocksize = priv->rwb.blocksize;
- geo->erasesize = priv->rwb.blocksize* priv->spb;
- geo->neraseblocks = priv->rwb.nblocks * priv->spb;
+ geo->erasesize = priv->rwb.blocksize * priv->spb;
+ geo->neraseblocks = priv->rwb.nblocks / priv->spb;
ret = OK;
fvdbg("blocksize: %d erasesize: %d neraseblocks: %d\n",
diff --git a/nuttx/drivers/rwbuffer.c b/nuttx/drivers/rwbuffer.c
index ee4328aa7..97c466eb3 100644
--- a/nuttx/drivers/rwbuffer.c
+++ b/nuttx/drivers/rwbuffer.c
@@ -150,6 +150,10 @@ static inline void rwb_resetwrbuffer(struct rwbuffer_s *rwb)
/****************************************************************************
* Name: rwb_wrflush
+ *
+ * Assumptions:
+ * The caller holds the wrsem semaphore.
+ *
****************************************************************************/
#ifdef CONFIG_DRVR_WRITEBUFFER
@@ -159,7 +163,6 @@ static void rwb_wrflush(struct rwbuffer_s *rwb)
fvdbg("Timeout!\n");
- rwb_semtake(&rwb->wrsem);
if (rwb->wrnblocks > 0)
{
fvdbg("Flushing: blockstart=0x%08lx nblocks=%d from buffer=%p\n",
@@ -179,7 +182,6 @@ static void rwb_wrflush(struct rwbuffer_s *rwb)
rwb_resetwrbuffer(rwb);
}
- rwb_semgive(&rwb->wrsem);
}
#endif
@@ -199,7 +201,9 @@ static void rwb_wrtimeout(FAR void *arg)
* worker thread.
*/
+ rwb_semtake(&rwb->wrsem);
rwb_wrflush(rwb);
+ rwb_semgive(&rwb->wrsem);
}
/****************************************************************************
@@ -341,17 +345,22 @@ rwb_bufferread(struct rwbuffer_s *rwb, off_t startblock,
#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
- * read-ahead buffer
- */
-
- off_t endblock = startblock + rwb->rhmaxblocks;
+ off_t endblock;
size_t nblocks;
int ret;
- /* Reset the read buffer */
+ /* Check for attempts to read beyond the end of the media */
- rwb_resetrhbuffer(rwb);
+ if (startblock >= rwb->nblocks)
+ {
+ return -ESPIPE;
+ }
+
+ /* Get the block number +1 of the last block that will fit in the
+ * read-ahead buffer
+ */
+
+ endblock = startblock + rwb->rhmaxblocks;
/* Make sure that we don't read past the end of the device */
@@ -362,6 +371,10 @@ static int rwb_rhreload(struct rwbuffer_s *rwb, off_t startblock)
nblocks = endblock - startblock;
+ /* Reset the read buffer */
+
+ rwb_resetrhbuffer(rwb);
+
/* Now perform the read */
ret = rwb->rhreload(rwb->dev, rwb->rhbuffer, startblock, nblocks);
@@ -471,13 +484,13 @@ int rwb_invalidate_writebuffer(FAR struct rwbuffer_s *rwb,
/* 4. We invalidate a portion at the beginning of the write buffer */
- else /* if (rwb->wrblockstart >= startblock && wrbend < invend) */
+ else /* if (rwb->wrblockstart >= startblock && wrbend > invend) */
{
uint8_t *src;
size_t ninval;
size_t nkeep;
- DEBUGASSERT(rwb->wrblockstart >= startblock && wrbend < invend);
+ DEBUGASSERT(rwb->wrblockstart >= startblock && wrbend > invend);
/* Copy the data from the uninvalidated region to the beginning
* of the write buffer.
@@ -548,7 +561,7 @@ int rwb_invalidate_readahead(FAR struct rwbuffer_s *rwb,
rhbend = rwb->rhblockstart + rwb->rhnblocks;
invend = startblock + blockcount;
- if (rwb->rhblockstart > invend || rhbend < startblock)
+ if (rhbend <= startblock || rwb->rhblockstart >= invend )
{
ret = OK;
}
@@ -564,7 +577,7 @@ int rwb_invalidate_readahead(FAR struct rwbuffer_s *rwb,
/* 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
+ * 2. We invalidate a portion in the middle of the read-ahead buffer
*/
else if (rwb->rhblockstart < startblock && rhbend > invend)
@@ -587,14 +600,14 @@ int rwb_invalidate_readahead(FAR struct rwbuffer_s *rwb,
/* 4. We invalidate a portion at the beginning of the write buffer */
- else /* if (rwb->rhblockstart >= startblock && rhbend < invend) */
+ 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);
+ DEBUGASSERT(rwb->rhblockstart >= startblock && rhbend > invend);
rwb->rhnblocks = 0;
ret = OK;
}
@@ -778,34 +791,25 @@ int rwb_read(FAR struct rwbuffer_s *rwb, off_t startblock, uint32_t nblocks,
if (rwb->rhnblocks > 0)
{
- off_t block = startblock;
- size_t nbufblocks = 0;
off_t bufferend;
- /* Loop for each block we find in the read-head buffer. Count
- * the number of buffers that we can read from read-ahead
- * buffer.
- */
+ /* How many blocks are available in this buffer? */
bufferend = rwb->rhblockstart + rwb->rhnblocks;
-
- while (block >= rwb->rhblockstart && block < bufferend && remaining > 0)
+ if (startblock >= rwb->rhblockstart && startblock < bufferend)
{
- /* This is one more that we will read from the read ahead
- * buffer.
- */
-
- nbufblocks++;
+ size_t rdblocks = bufferend - startblock;
+ if (rdblocks > remaining)
+ {
+ rdblocks = 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, rdblocks, &rdbuffer);
+ startblock += rdblocks;
+ remaining -= rdblocks;
}
-
- /* Then read the data from the read-ahead buffer */
-
- rwb_bufferread(rwb, startblock, nbufblocks, &rdbuffer);
}
/* If we did not get all of the data from the buffer, then we have
@@ -920,6 +924,32 @@ int rwb_write(FAR struct rwbuffer_s *rwb, off_t startblock,
}
/****************************************************************************
+ * Name: rwb_readbytes
+ *
+ * Description:
+ * Character-oriented read
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DRVR_READBYTES
+ssize_t rwb_readbytes(FAR struct rwbuffer_s *dev, off_t offset,
+ size_t nbytes, FAR uint8_t *buffer)
+{
+ /* Loop while there are bytes still be be read */
+ /* Make sure that the sector containing the next bytes to transfer is in
+ * memory.
+ */
+ /* How many bytes can be transfer from the in-memory data? */
+ /* Transfer the bytes */
+ /* Adjust counts and offsets for the next time through the loop */
+
+#warning Not Implemented
+ return -ENOSYS;
+}
+#endif
+
+
+/****************************************************************************
* Name: rwb_mediaremoved
*
* Description: