summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-05-28 17:51:24 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-05-28 17:51:24 +0000
commit6292602b85b085b1579cbc8bb6def5035f1abdf7 (patch)
tree22f8de1d73701910fa0149354df7d8b660a6ee0e /nuttx
parent2547315d49a4ee9f2fc61d54260a8b1f37f33cbd (diff)
downloadpx4-nuttx-6292602b85b085b1579cbc8bb6def5035f1abdf7.tar.gz
px4-nuttx-6292602b85b085b1579cbc8bb6def5035f1abdf7.tar.bz2
px4-nuttx-6292602b85b085b1579cbc8bb6def5035f1abdf7.zip
Final integration of microSD
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1830 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rwxr-xr-xnuttx/arch/arm/src/lm3s/lm3s_ssi.c46
-rw-r--r--nuttx/configs/README.txt1
-rw-r--r--nuttx/configs/eagle100/README.txt4
-rw-r--r--nuttx/configs/eagle100/httpd/defconfig7
-rw-r--r--nuttx/configs/eagle100/nettest/defconfig7
-rw-r--r--nuttx/configs/eagle100/nsh/defconfig7
-rw-r--r--nuttx/configs/eagle100/ostest/defconfig7
-rw-r--r--nuttx/drivers/mmcsd/mmcsd_spi.c86
8 files changed, 144 insertions, 21 deletions
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_ssi.c b/nuttx/arch/arm/src/lm3s/lm3s_ssi.c
index ae45dbf97..3df87ecb2 100755
--- a/nuttx/arch/arm/src/lm3s/lm3s_ssi.c
+++ b/nuttx/arch/arm/src/lm3s/lm3s_ssi.c
@@ -122,6 +122,20 @@
#define LM3S_TXFIFO_WORDS 8
+/* Configuration settings */
+
+#ifndef CONFIG_SSI_TXLIMIT
+# define CONFIG_SSI_TXLIMIT (LM3S_TXFIFO_WORDS/2)
+#endif
+
+#if CONFIG_SSI_TXLIMIT < 1 || CONFIG_SSI_TXLIMIT > LM3S_TXFIFO_WORDS
+# error "Invalid range for CONFIG_SSI_TXLIMIT
+#endif
+
+#ifndef CONFIG_SSI_TXLIMIT && CONFIG_SSI_TXLIMIT < (LM3S_TXFIFO_WORDS/2)
+# error "CONFIG_SSI_TXLIMIT must be at least half the TX FIFO size"
+#endif
+
/****************************************************************************
* Private Type Definitions
****************************************************************************/
@@ -196,7 +210,11 @@ static void ssi_rxuint16(struct lm32_ssidev_s *priv);
static void ssi_rxubyte(struct lm32_ssidev_s *priv);
static inline boolean ssi_txfifofull(struct lm32_ssidev_s *priv);
static inline boolean ssi_rxfifoempty(struct lm32_ssidev_s *priv);
+#if CONFIG_SSI_TXLIMIT == 1 && defined(CONFIG_SSI_POLLWAIT)
+static inline int ssi_performtx(struct lm32_ssidev_s *priv);
+#else
static int ssi_performtx(struct lm32_ssidev_s *priv);
+#endif
static inline void ssi_performrx(struct lm32_ssidev_s *priv);
static int ssi_transfer(struct lm32_ssidev_s *priv, const void *txbuffer,
void *rxbuffer, unsigned int nwords);
@@ -543,6 +561,24 @@ static inline boolean ssi_rxfifoempty(struct lm32_ssidev_s *priv)
*
****************************************************************************/
+#if CONFIG_SSI_TXLIMIT == 1 && defined(CONFIG_SSI_POLLWAIT)
+static inline int ssi_performtx(struct lm32_ssidev_s *priv)
+{
+ /* Check if the Tx FIFO is full and more data to transfer */
+
+ if (!ssi_txfifofull(priv) && priv->ntxwords > 0)
+ {
+ /* Transfer one word to the Tx FIFO */
+
+ priv->txword(priv);
+ priv->ntxwords--;
+ return 1;
+ }
+ return 0;
+}
+
+#else /* CONFIG_SSI_TXLIMIT == 1 CONFIG_SSI_POLLWAIT */
+
static int ssi_performtx(struct lm32_ssidev_s *priv)
{
#ifndef CONFIG_SSI_POLLWAIT
@@ -561,12 +597,12 @@ static int ssi_performtx(struct lm32_ssidev_s *priv)
/* No.. Transfer more words until either the Tx FIFO is full or
* until all of the user provided data has been sent.
*/
-#if 1
+#ifdef CONFIG_SSI_TXLIMIT
/* Further limit the number of words that we put into the Tx
- * FIFO to half the half the FIFO depth. Otherwise, we could
+ * FIFO to CONFIG_SSI_TXLIMIT. Otherwise, we could
* overrun the Rx FIFO on a very fast SSI bus.
*/
- for (; ntxd < priv->ntxwords && ntxd < LM3S_TXFIFO_WORDS/2 && !ssi_txfifofull(priv); ntxd++)
+ for (; ntxd < priv->ntxwords && ntxd < CONFIG_SSI_TXLIMIT && !ssi_txfifofull(priv); ntxd++)
#else
for (; ntxd < priv->ntxwords && !ssi_txfifofull(priv); ntxd++)
#endif
@@ -609,6 +645,8 @@ static int ssi_performtx(struct lm32_ssidev_s *priv)
return ntxd;
}
+#endif /* CONFIG_SSI_TXLIMIT == 1 CONFIG_SSI_POLLWAIT */
+
/****************************************************************************
* Name: ssi_performrx
*
@@ -751,6 +789,7 @@ static int ssi_transfer(struct lm32_ssidev_s *priv, const void *txbuffer,
ssivdbg("ntxwords: %d nrxwords: %d nwords: %d SR: %08x\n",
priv->ntxwords, priv->nrxwords, priv->nwords,
ssi_getreg(priv, LM3S_SSI_SR_OFFSET));
+
ntxd = ssi_performtx(priv);
/* For the case where nwords < Tx FIFO size, ssi_performrx will
@@ -759,6 +798,7 @@ static int ssi_transfer(struct lm32_ssidev_s *priv, const void *txbuffer,
*/
ssi_performrx(priv);
+
ssivdbg("ntxwords: %d nrxwords: %d nwords: %d SR: %08x IM: %08x\n",
priv->ntxwords, priv->nrxwords, priv->nwords,
ssi_getreg(priv, LM3S_SSI_SR_OFFSET),
diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt
index 2dba9d0f5..36c422f46 100644
--- a/nuttx/configs/README.txt
+++ b/nuttx/configs/README.txt
@@ -139,7 +139,6 @@ defconfig -- This is a configuration file similar to the Linux
CONFIG_DRAM_START - The start address of DRAM (physical)
CONFIG_DRAM_VSTART - The start address of DRAM (virtual)
-
General build options
CONFIG_RRLOAD_BINARY - make the rrload binary format used with
diff --git a/nuttx/configs/eagle100/README.txt b/nuttx/configs/eagle100/README.txt
index cc6cf3944..4182582bd 100644
--- a/nuttx/configs/eagle100/README.txt
+++ b/nuttx/configs/eagle100/README.txt
@@ -205,6 +205,10 @@ Eagle100-specific Configuration Options
CONFIG_SSI_POLLWAIT - Select to disable interrupt driven SSI support.
Poll-waiting is recommended if the interrupt rate would be to
high in the interrupt driven case.
+ CONFIG_SSI_TXLIMIT - Write this many words to the Tx FIFO before
+ emptying the Rx FIFO. If the SPI frequency is high and this
+ value is large, then larger values of this setting may cause
+ Rx FIFO overrun errors. Default: half of the Tx FIFO size (4).
CONFIG_LM3S_ETHERNET - This must be set (along with CONFIG_NET)
to build the LM3S Ethernet driver
diff --git a/nuttx/configs/eagle100/httpd/defconfig b/nuttx/configs/eagle100/httpd/defconfig
index d6aa384a5..8f410917d 100644
--- a/nuttx/configs/eagle100/httpd/defconfig
+++ b/nuttx/configs/eagle100/httpd/defconfig
@@ -126,10 +126,17 @@ CONFIG_UART1_2STOP=0
# CONFIG_SSIn_DISABLE - select to disable all support for
# the SSI
# CONFIG_SSI_POLLWAIT - Select to disable interrupt driven SSI support
+# Poll-waiting is recommended if the interrupt rate would be to
+# high in the interrupt driven case.
+# CONFIG_SSI_TXLIMIT - Write this many words to the Tx FIFO before
+# emptying the Rx FIFO. If the SPI frequency is high and this
+# value is large, then larger values of this setting may cause
+# Rx FIFO overrun errors. Default: half of the Tx FIFO size (4).
#
CONFIG_SSI0_DISABLE=n
CONFIG_SSI1_DISABLE=y
CONFIG_SSI_POLLWAIT=y
+#CONFIG_SSI_TXLIMIT=4
#
# LM3S6918 specific serial device driver settings
diff --git a/nuttx/configs/eagle100/nettest/defconfig b/nuttx/configs/eagle100/nettest/defconfig
index 1bd4c2320..96d82f693 100644
--- a/nuttx/configs/eagle100/nettest/defconfig
+++ b/nuttx/configs/eagle100/nettest/defconfig
@@ -126,10 +126,17 @@ CONFIG_UART1_2STOP=0
# CONFIG_SSIn_DISABLE - select to disable all support for
# the SSI
# CONFIG_SSI_POLLWAIT - Select to disable interrupt driven SSI support
+# Poll-waiting is recommended if the interrupt rate would be to
+# high in the interrupt driven case.
+# CONFIG_SSI_TXLIMIT - Write this many words to the Tx FIFO before
+# emptying the Rx FIFO. If the SPI frequency is high and this
+# value is large, then larger values of this setting may cause
+# Rx FIFO overrun errors. Default: half of the Tx FIFO size (4).
#
CONFIG_SSI0_DISABLE=n
CONFIG_SSI1_DISABLE=y
CONFIG_SSI_POLLWAIT=y
+#CONFIG_SSI_TXLIMIT=4
#
# LM3S6918 specific serial device driver settings
diff --git a/nuttx/configs/eagle100/nsh/defconfig b/nuttx/configs/eagle100/nsh/defconfig
index 1fab6e4a2..cbd62632f 100644
--- a/nuttx/configs/eagle100/nsh/defconfig
+++ b/nuttx/configs/eagle100/nsh/defconfig
@@ -126,10 +126,17 @@ CONFIG_UART1_2STOP=0
# CONFIG_SSIn_DISABLE - select to disable all support for
# the SSI
# CONFIG_SSI_POLLWAIT - Select to disable interrupt driven SSI support
+# Poll-waiting is recommended if the interrupt rate would be to
+# high in the interrupt driven case.
+# CONFIG_SSI_TXLIMIT - Write this many words to the Tx FIFO before
+# emptying the Rx FIFO. If the SPI frequency is high and this
+# value is large, then larger values of this setting may cause
+# Rx FIFO overrun errors. Default: half of the Tx FIFO size (4).
#
CONFIG_SSI0_DISABLE=n
CONFIG_SSI1_DISABLE=y
CONFIG_SSI_POLLWAIT=y
+#CONFIG_SSI_TXLIMIT=4
#
# LM3S6918 specific serial device driver settings
diff --git a/nuttx/configs/eagle100/ostest/defconfig b/nuttx/configs/eagle100/ostest/defconfig
index c8f5ef36a..066703054 100644
--- a/nuttx/configs/eagle100/ostest/defconfig
+++ b/nuttx/configs/eagle100/ostest/defconfig
@@ -126,10 +126,17 @@ CONFIG_UART1_2STOP=0
# CONFIG_SSIn_DISABLE - select to disable all support for
# the SSI
# CONFIG_SSI_POLLWAIT - Select to disable interrupt driven SSI support
+# Poll-waiting is recommended if the interrupt rate would be to
+# high in the interrupt driven case.
+# CONFIG_SSI_TXLIMIT - Write this many words to the Tx FIFO before
+# emptying the Rx FIFO. If the SPI frequency is high and this
+# value is large, then larger values of this setting may cause
+# Rx FIFO overrun errors. Default: half of the Tx FIFO size (4).
#
CONFIG_SSI0_DISABLE=n
CONFIG_SSI1_DISABLE=y
CONFIG_SSI_POLLWAIT=y
+#CONFIG_SSI_TXLIMIT=4
#
# LM3S6918 specific serial device driver settings
diff --git a/nuttx/drivers/mmcsd/mmcsd_spi.c b/nuttx/drivers/mmcsd/mmcsd_spi.c
index e7f81e16f..637ec2e04 100644
--- a/nuttx/drivers/mmcsd/mmcsd_spi.c
+++ b/nuttx/drivers/mmcsd/mmcsd_spi.c
@@ -81,6 +81,10 @@
# define CONFIG_MMCSD_SPICLOCK 20000000
#endif
+#ifndef CONFIG_MMCSD_SECTOR512
+# define CONFIG_MMCSD_SECTOR512 /* Force 512 byte sectors on all cards */
+#endif
+
/* Slot struct info *********************************************************/
/* Slot status definitions */
@@ -98,6 +102,12 @@
#define MMCSD_CMDRESP_R3 3
#define MMCSD_CMDRESP_R7 4
+#ifdef CONFIG_MMCSD_SECTOR512
+# define SECTORSIZE(s) (512)
+#else
+# define SECTORSIZE(s) ((s)->sectorsize)
+#endif
+
/* Time delays in units of the system clock. CLK_TCK is the number of clock
* ticks per second.
*/
@@ -131,7 +141,9 @@ struct mmcsd_slot_s
ubyte state; /* State of the slot (see MMCSD_SLOTSTATUS_* definitions) */
ubyte type; /* Disk type */
ubyte csd[16]; /* Copy of card CSD */
+#ifndef CONFIG_MMCSD_SECTOR512
uint16 sectorsize; /* Media block size (in bytes) */
+#endif
uint32 nsectors; /* Number of blocks on the media */
uint32 taccess; /* Card access time */
uint32 twrite; /* Card write time */
@@ -707,21 +719,37 @@ static void mmcsd_decodecsd(FAR struct mmcsd_slot_s *slot, ubyte *csd)
csize = MMCSD_CSD_CSIZE(csd) + 1;
}
- /* SDHC cards have fixed sector size of 512 bytes */
+ /* SDHC ver2.x cards have fixed block transfer size of 512 bytes. SDC
+ * ver1.x cards with capacity less than 1Gb, will have sector size
+ * 512 byes. SDC ver1.x cards with capacity of 2Gb will report readbllen
+ * of 1024 but should use 512 bytes for block transfers. SDC ver1.x 4Gb
+ * cards will report readbllen of 2048 bytes -- are they also 512 bytes?
+ */
+#ifdef CONFIG_MMCSD_SECTOR512
+ if (readbllen > 9)
+ {
+ csizemult += (readbllen - 9);
+ }
+ else
+ {
+ DEBUGASSERT(readbllen == 9);
+ }
+#else
if (IS_SDV2(slot->type))
{
if (readbllen > 9)
{
fdbg("Forcing 512 byte sector size\n");
- csizemult += (readbllen - 9);
- readbllen = 9;
+ csizemult += (readbllen - 9);
+ readbllen = 9;
}
}
slot->sectorsize = 1 << readbllen;
+#endif
slot->nsectors = csize << csizemult;
- fvdbg("Sector size: %d\n", slot->sectorsize);
+ fvdbg("Sector size: %d\n", SECTORSIZE(slot));
fvdbg("Number of sectors: %d\n", slot->nsectors);
}
@@ -1037,7 +1065,7 @@ static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer,
/* Convert sector and nsectors to nbytes and byte offset */
- nbytes = nsectors * slot->sectorsize;
+ nbytes = nsectors * SECTORSIZE(slot);
if (IS_BLOCK(slot->type))
{
offset = start_sector;
@@ -1045,7 +1073,7 @@ static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer,
}
else
{
- offset = start_sector * slot->sectorsize;
+ offset = start_sector * SECTORSIZE(slot);
fvdbg("nbytes=%d byte offset=%d\n", nbytes, offset);
}
@@ -1072,7 +1100,7 @@ static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer,
/* Receive the block */
- if (mmcsd_recvblock(slot, buffer, slot->sectorsize) != 0)
+ if (mmcsd_recvblock(slot, buffer, SECTORSIZE(slot)) != 0)
{
fdbg("Failed: to receive the block\n");
goto errout_with_eio;
@@ -1095,12 +1123,12 @@ static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer,
for (i = 0; i < nsectors; i++)
{
- if (mmcsd_recvblock(slot, buffer, slot->sectorsize) != 0)
+ if (mmcsd_recvblock(slot, buffer, SECTORSIZE(slot)) != 0)
{
fdbg("Failed: to receive the block\n");
goto errout_with_eio;
}
- buffer += slot->sectorsize;
+ buffer += SECTORSIZE(slot);
}
/* Send CMD12: Stops transmission */
@@ -1198,7 +1226,7 @@ static ssize_t mmcsd_write(FAR struct inode *inode, const unsigned char *buffer,
/* Convert sector and nsectors to nbytes and byte offset */
- nbytes = nsectors * slot->sectorsize;
+ nbytes = nsectors * SECTORSIZE(slot);
if (IS_BLOCK(slot->type))
{
offset = start_sector;
@@ -1206,7 +1234,7 @@ static ssize_t mmcsd_write(FAR struct inode *inode, const unsigned char *buffer,
}
else
{
- offset = start_sector * slot->sectorsize;
+ offset = start_sector * SECTORSIZE(slot);
fvdbg("nbytes=%d byte offset=%d\n", nbytes, offset);
}
mmcsd_dumpbuffer(buffer, nbytes);
@@ -1232,7 +1260,7 @@ static ssize_t mmcsd_write(FAR struct inode *inode, const unsigned char *buffer,
/* Then transfer the sector */
- if (mmcsd_xmitblock(slot, buffer, slot->sectorsize, 0xfe) != 0)
+ if (mmcsd_xmitblock(slot, buffer, SECTORSIZE(slot), 0xfe) != 0)
{
fdbg("Block transfer failed\n");
goto errout_with_sem;
@@ -1267,12 +1295,12 @@ static ssize_t mmcsd_write(FAR struct inode *inode, const unsigned char *buffer,
for (i = 0; i < nsectors; i++)
{
- if (mmcsd_xmitblock(slot, buffer, slot->sectorsize, 0xfc) != 0)
+ if (mmcsd_xmitblock(slot, buffer, SECTORSIZE(slot), 0xfc) != 0)
{
fdbg("Failed: to receive the block\n");
goto errout_with_sem;
}
- buffer += slot->sectorsize;
+ buffer += SECTORSIZE(slot);
}
/* Send the stop transmission token */
@@ -1371,7 +1399,7 @@ static int mmcsd_geometry(FAR struct inode *inode, struct geometry *geometry)
geometry->geo_writeenabled = FALSE;
#endif
geometry->geo_nsectors = slot->nsectors;
- geometry->geo_sectorsize = slot->sectorsize;
+ geometry->geo_sectorsize = SECTORSIZE(slot);
/* After reporting mediachanged, clear the indication so that it is not
* reported again.
@@ -1629,12 +1657,36 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot)
mmcsd_decodecsd(slot, csd);
mmcsd_checkwrprotect(slot, csd);
- /* SD Version 2.xx block length is always 512 */
+ /* SDHC ver2.x cards have fixed block transfer size of 512 bytes. SDC
+ * ver1.x cards with capacity less than 1Gb, will have sector size
+ * 512 byes. SDC ver1.x cards with capacity of 2Gb will report readbllen
+ * of 1024 but should use 512 bytes for block transfers. SDC ver1.x 4Gb
+ * cards will report readbllen of 2048 bytes -- are they also 512 bytes?
+ * I think that none of these high capacity cards support setting the
+ * block length??
+ */
+#ifdef CONFIG_MMCSD_SECTOR512
+ /* Using 512 byte sectors, the maximum ver1.x capacity is 4096 x 512 blocks.
+ * The saved slot->nsectors is converted to 512 byte blocks, so if slot->nsectors
+ * exceeds 4096 x 512, then we must be dealing with a card with read_bl_len
+ * of 1024 or 2048.
+ */
+
+ if (!IS_SDV2(slot->type) && slot->nsectors <= 4096*12)
+ {
+ /* Don't set the block len on high capacity cards (ver1.x or ver2.x) */
+
+ mmcsd_setblklen(slot, SECTORSIZE(slot));
+ }
+#else
if (!IS_SDV2(slot->type))
{
- mmcsd_setblklen(slot, slot->sectorsize);
+ /* Don't set the block len on ver2.x cards */
+
+ mmcsd_setblklen(slot, SECTORSIZE(slot));
}
+#endif
slot->state &= ~MMCSD_SLOTSTATUS_NOTREADY;
SPI_SELECT(spi, SPIDEV_MMCSD, FALSE);