summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog3
-rw-r--r--nuttx/Documentation/NuttX.html5
-rw-r--r--nuttx/Documentation/NuttxPortingGuide.html8
-rw-r--r--nuttx/Makefile6
-rw-r--r--nuttx/configs/README.txt1
-rw-r--r--nuttx/configs/eagle100/httpd/defconfig3
-rw-r--r--nuttx/configs/eagle100/nettest/defconfig3
-rw-r--r--nuttx/configs/eagle100/nsh/defconfig3
-rw-r--r--nuttx/configs/eagle100/ostest/defconfig3
-rw-r--r--nuttx/configs/mcu123-lpc214x/nsh/defconfig14
-rw-r--r--nuttx/configs/mcu123-lpc214x/ostest/defconfig7
-rw-r--r--nuttx/configs/mcu123-lpc214x/src/up_spi.c49
-rw-r--r--nuttx/configs/mcu123-lpc214x/usbserial/defconfig7
-rw-r--r--nuttx/configs/mcu123-lpc214x/usbstorage/defconfig7
-rw-r--r--nuttx/drivers/mmcsd/mmcsd_spi.c51
15 files changed, 154 insertions, 16 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 222129763..95fced4fe 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -746,5 +746,8 @@
* configs/eagle100/*/Make.defs: Added configuration options that should make
it possible to build NuttX for the Eagle100 using CodeSourcery 2009q1 toolchain
and the devkitARM GNU toolchain.
+ * configs/mcu123-lpc214x/src: Corrected some logic in the LPC2148 SPI receive block
+ logic. Re-verified SDC ver1.x support with 1Gb Toshiba SDC, 1Gb PNY SDC, 2Gb SanDisk SDC,
+ and 4Gb Kingston SDHC.
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index 107e2d774..035d5d084 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -8,7 +8,7 @@
<tr align="center" bgcolor="#e4e4e4">
<td>
<h1><big><font color="#3c34ec"><i>NuttX RTOS</i></font></big></h1>
- <p>Last Updated: May 27, 2009</p>
+ <p>Last Updated: May 28, 2009</p>
</td>
</tr>
</table>
@@ -1436,6 +1436,9 @@ nuttx-0.4.7 2009-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
* configs/eagle100/*/Make.defs: Added configuration options that should make
it possible to build NuttX for the Eagle100 using CodeSourcery 2009q1 toolchain
and the devkitARM GNU toolchain.
+ * configs/mcu123-lpc214x/src: Corrected some logic in the LPC2148 SPI receive block
+ logic. Re-verified SDC ver1.x support with 1Gb Toshiba SDC, 1Gb PNY SDC, 2Gb SanDisk SDC,
+ and 4Gb Kingston SDHC.
pascal-0.1.3 2009-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html
index d78be1b14..6ab70d961 100644
--- a/nuttx/Documentation/NuttxPortingGuide.html
+++ b/nuttx/Documentation/NuttxPortingGuide.html
@@ -12,7 +12,7 @@
<h1><big><font color="#3c34ec">
<i>NuttX RTOS Porting Guide</i>
</font></big></h1>
- <p>Last Updated: May 22, 2009</p>
+ <p>Last Updated: May 28, 2009</p>
</td>
</tr>
</table>
@@ -2180,6 +2180,12 @@ extern void up_ledoff(int led);
<li>
<code>CONFIG_MMCSD_READONLY</code>: Provide read-only access. Default is Read/Write
</li>
+ <li>
+ <code>CONFIG_MMCSD_SPICLOCK</code>: Maximum SPI clock to drive MMC/SD card. Default is 20MHz.
+ </li>
+ <li>
+ <code>CONFIG_MMCSD_SYNCHRONIZE</code>: Special synchronization logic needed
+ </li>
</ul>
<h2>Network Support</h2>
diff --git a/nuttx/Makefile b/nuttx/Makefile
index d448b2a82..432672ef3 100644
--- a/nuttx/Makefile
+++ b/nuttx/Makefile
@@ -1,7 +1,7 @@
############################################################################
# Makefile
#
-# Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+# Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
#
# Redistribution and use in source and binary forms, with or without
@@ -268,7 +268,7 @@ subdir_clean:
@$(MAKE) -C tools -f Makefile.mkconfig TOPDIR="$(TOPDIR)" clean
@$(MAKE) -C mm -f Makefile.test TOPDIR="$(TOPDIR)" clean
-clean: subdir_clean clean_context
+clean: subdir_clean
@rm -f $(BIN) nuttx.* mm_test *.map *~
subdir_distclean:
@@ -278,7 +278,7 @@ subdir_distclean:
fi \
done
-distclean: clean subdir_distclean
+distclean: clean subdir_distclean clean_context
@rm -f Make.defs setenv.sh .config
diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt
index 36c422f46..5443eb75e 100644
--- a/nuttx/configs/README.txt
+++ b/nuttx/configs/README.txt
@@ -287,6 +287,7 @@ defconfig -- This is a configuration file similar to the Linux
Read/Write
CONFIG_MMCSD_SPICLOCK - Maximum SPI clock to drive MMC/SD card.
Default is 20MHz.
+ CONFIG_MMCSD_SYNCHRONIZE - Special synchronization logic needed
TCP/IP and UDP support via uIP
CONFIG_NET - Enable or disable all network features
diff --git a/nuttx/configs/eagle100/httpd/defconfig b/nuttx/configs/eagle100/httpd/defconfig
index 8f410917d..9c42f6583 100644
--- a/nuttx/configs/eagle100/httpd/defconfig
+++ b/nuttx/configs/eagle100/httpd/defconfig
@@ -359,10 +359,13 @@ CONFIG_FS_ROMFS=n
# Provide read-only access (default is read/write)
# CONFIG_MMCSD_SPICLOCK - Maximum SPI clock to drive MMC/SD card.
# Default is 20MHz.
+# CONFIG_MMCSD_SYNCHRONIZE
+# Special synchronization logic needed
#
CONFIG_MMCSD_NSLOTS=1
CONFIG_MMCSD_READONLY=n
CONFIG_MMCSD_SPICLOCK=12500000
+CONFIG_MMCSD_SYNCHRONIZE=n
#
# TCP/IP and UDP support via uIP
diff --git a/nuttx/configs/eagle100/nettest/defconfig b/nuttx/configs/eagle100/nettest/defconfig
index 96d82f693..8b501a9d1 100644
--- a/nuttx/configs/eagle100/nettest/defconfig
+++ b/nuttx/configs/eagle100/nettest/defconfig
@@ -359,10 +359,13 @@ CONFIG_FS_ROMFS=n
# Provide read-only access (default is read/write)
# CONFIG_MMCSD_SPICLOCK - Maximum SPI clock to drive MMC/SD card.
# Default is 20MHz.
+# CONFIG_MMCSD_SYNCHRONIZE
+# Special synchronization logic needed
#
CONFIG_MMCSD_NSLOTS=1
CONFIG_MMCSD_READONLY=n
CONFIG_MMCSD_SPICLOCK=12500000
+CONFIG_MMCSD_SYNCHRONIZE=n
#
# TCP/IP and UDP support via uIP
diff --git a/nuttx/configs/eagle100/nsh/defconfig b/nuttx/configs/eagle100/nsh/defconfig
index cbd62632f..6bd803948 100644
--- a/nuttx/configs/eagle100/nsh/defconfig
+++ b/nuttx/configs/eagle100/nsh/defconfig
@@ -358,10 +358,13 @@ CONFIG_FS_ROMFS=n
# Provide read-only access (default is read/write)
# CONFIG_MMCSD_SPICLOCK - Maximum SPI clock to drive MMC/SD card.
# Default is 20MHz.
+# CONFIG_MMCSD_SYNCHRONIZE
+# Special synchronization logic needed
#
CONFIG_MMCSD_NSLOTS=1
CONFIG_MMCSD_READONLY=n
CONFIG_MMCSD_SPICLOCK=12500000
+CONFIG_MMCSD_SYNCHRONIZE=n
#
# TCP/IP and UDP support via uIP
diff --git a/nuttx/configs/eagle100/ostest/defconfig b/nuttx/configs/eagle100/ostest/defconfig
index 066703054..2abbbb648 100644
--- a/nuttx/configs/eagle100/ostest/defconfig
+++ b/nuttx/configs/eagle100/ostest/defconfig
@@ -358,10 +358,13 @@ CONFIG_FS_ROMFS=n
# Provide read-only access (default is read/write)
# CONFIG_MMCSD_SPICLOCK - Maximum SPI clock to drive MMC/SD card.
# Default is 20MHz.
+# CONFIG_MMCSD_SYNCHRONIZE
+# Special synchronization logic needed
#
CONFIG_MMCSD_NSLOTS=1
CONFIG_MMCSD_READONLY=n
CONFIG_MMCSD_SPICLOCK=12500000
+CONFIG_MMCSD_SYNCHRONIZE=n
#
# TCP/IP and UDP support via uIP
diff --git a/nuttx/configs/mcu123-lpc214x/nsh/defconfig b/nuttx/configs/mcu123-lpc214x/nsh/defconfig
index 36a939f45..fd55a8f22 100644
--- a/nuttx/configs/mcu123-lpc214x/nsh/defconfig
+++ b/nuttx/configs/mcu123-lpc214x/nsh/defconfig
@@ -301,9 +301,21 @@ CONFIG_FS_FAT=y
CONFIG_FS_ROMFS=n
#
-# MMC/SD configuration
+# SPI-based MMC/SD driver
+#
+# CONFIG_MMCSD_NSLOTS
+# Number of MMC/SD slots supported by the driver
+# CONFIG_MMCSD_READONLY
+# Provide read-only access (default is read/write)
+# CONFIG_MMCSD_SPICLOCK - Maximum SPI clock to drive MMC/SD card.
+# Default is 20MHz.
+# CONFIG_MMCSD_SYNCHRONIZE
+# Special synchronization logic needed
+#
CONFIG_MMCSD_NSLOTS=1
CONFIG_MMCSD_READONLY=n
+#CONFIG_MMCSD_SPICLOCK=20000000
+CONFIG_MMCSD_SYNCHRONIZE=y
#
# SPI-based MMC/SD driver
diff --git a/nuttx/configs/mcu123-lpc214x/ostest/defconfig b/nuttx/configs/mcu123-lpc214x/ostest/defconfig
index a842b82c0..28dac142b 100644
--- a/nuttx/configs/mcu123-lpc214x/ostest/defconfig
+++ b/nuttx/configs/mcu123-lpc214x/ostest/defconfig
@@ -303,8 +303,15 @@ CONFIG_FS_ROMFS=n
# Number of MMC/SD slots supported by the driver
# CONFIG_MMCSD_READONLY
# Provide read-only access (default is read/write)
+# CONFIG_MMCSD_SPICLOCK - Maximum SPI clock to drive MMC/SD card.
+# Default is 20MHz.
+# CONFIG_MMCSD_SYNCHRONIZE
+# Special synchronization logic needed
+#
CONFIG_MMCSD_NSLOTS=1
CONFIG_MMCSD_READONLY=n
+#CONFIG_MMCSD_SPICLOCK=20000000
+CONFIG_MMCSD_SYNCHRONIZE=y
#
# TCP/IP and UDP support via uIP
diff --git a/nuttx/configs/mcu123-lpc214x/src/up_spi.c b/nuttx/configs/mcu123-lpc214x/src/up_spi.c
index 59818748a..f2ca5196d 100644
--- a/nuttx/configs/mcu123-lpc214x/src/up_spi.c
+++ b/nuttx/configs/mcu123-lpc214x/src/up_spi.c
@@ -62,6 +62,7 @@
#include <nuttx/config.h>
#include <nuttx/spi.h>
+#include <debug.h>
#include <arch/board/board.h>
#include <nuttx/arch.h>
@@ -79,9 +80,31 @@
* Definitions
****************************************************************************/
+/* Enables debug output from this file (needs CONFIG_DEBUG too) */
+
+#undef SPI_DEBUG /* Define to enable debug */
+#undef SPI_VERBOSE /* Define to enable verbose debug */
+
+#ifdef SPI_DEBUG
+# define spidbg lldbg
+# ifdef SPI_VERBOSE
+# define spivdbg lldbg
+# else
+# define spivdbg(x...)
+# endif
+#else
+# undef SPI_VERBOSE
+# define spidbg(x...)
+# define spivdbg(x...)
+#endif
+
+/* Clocking */
+
#define LPC214X_CCLKFREQ (LPC214X_FOSC*LPC214X_PLL_M)
#define LPC214X_PCLKFREQ (LPC214X_CCLKFREQ/LPC214X_APB_DIV)
+/* Use either FIO or legacy GPIO */
+
#ifdef CONFIG_LPC214x_FIO
# define CS_SET_REGISTER (LPC214X_FIO0_BASE+LPC214X_FIO_SET_OFFSET)
# define CS_CLR_REGISTER (LPC214X_FIO0_BASE+LPC214X_FIO_CLR_OFFSET)
@@ -153,12 +176,14 @@ static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, boolean
{
/* Enable slave select (low enables) */
+ spidbg("CD asserted\n");
putreg32(bit, CS_CLR_REGISTER);
}
else
{
/* Disable slave select (low enables) */
+ spidbg("CD de-asserted\n");
putreg32(bit, CS_SET_REGISTER);
/* Wait for the TX FIFO not full indication */
@@ -214,6 +239,8 @@ static uint32 spi_setfrequency(FAR struct spi_dev_s *dev, uint32 frequency)
divisor = (divisor + 1) & ~1;
putreg8(divisor, LPC214X_SPI1_CPSR);
+
+ spidbg("Frequency %d->%d\n", frequency, LPC214X_PCLKFREQ / divisor);
return LPC214X_PCLKFREQ / divisor;
}
@@ -238,6 +265,7 @@ static ubyte spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
* board.
*/
+ spidbg("Return SPI_STATUS_PRESENT\n");
return SPI_STATUS_PRESENT;
}
@@ -259,6 +287,8 @@ static ubyte spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
static uint16 spi_send(FAR struct spi_dev_s *dev, uint16 wd)
{
+ register uint16 regval;
+
/* Wait while the TX FIFO is full */
while (!(getreg8(LPC214X_SPI1_SR) & LPC214X_SPI1SR_TNF));
@@ -273,7 +303,9 @@ static uint16 spi_send(FAR struct spi_dev_s *dev, uint16 wd)
/* Get the value from the RX FIFO and return it */
- return (uint16)getreg16(LPC214X_SPI1_DR);
+ regval = getreg16(LPC214X_SPI1_DR);
+ spidbg("%04x->%04x\n", wd, regval);
+ return regval;
}
/*************************************************************************
@@ -302,6 +334,7 @@ static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size
/* Loop while thre are bytes remaining to be sent */
+ spidbg("nwords: %d\n", nwords);
while (nwords > 0)
{
/* While the TX FIFO is not full and there are bytes left to send */
@@ -318,6 +351,7 @@ static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size
/* Then discard all card responses until the RX & TX FIFOs are emptied. */
+ spidbg("discarding\n");
do
{
/* Is there anything in the RX fifo? */
@@ -367,11 +401,12 @@ static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size
static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t nwords)
{
FAR ubyte *ptr = (FAR ubyte*)buffer;
- uint32 fifobytes = 0;
+ uint32 rxpending = 0;
/* While there is remaining to be sent (and no synchronization error has occurred) */
- while (ptr || fifobytes)
+ spidbg("nwords: %d\n", nwords);
+ while (nwords || rxpending)
{
/* Fill the transmit FIFO with 0xff...
* Write 0xff to the data register while (1) the TX FIFO is
@@ -379,20 +414,22 @@ static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t nw
* and (3) there are more bytes to be sent.
*/
+ spivdbg("TX: rxpending: %d nwords: %d\n", rxpending, nwords);
while ((getreg8(LPC214X_SPI1_SR) & LPC214X_SPI1SR_TNF) &&
- (fifobytes < LPC214X_SPI1_FIFOSZ) && nwords)
+ (rxpending < LPC214X_SPI1_FIFOSZ) && nwords)
{
putreg16(0xff, LPC214X_SPI1_DR);
nwords--;
- fifobytes++;
+ rxpending++;
}
/* Now, read the RX data from the RX FIFO while the RX FIFO is not empty */
+ spivdbg("RX: rxpending: %d\n", rxpending);
while (getreg8(LPC214X_SPI1_SR) & LPC214X_SPI1SR_RNE)
{
*ptr++ = (ubyte)getreg16(LPC214X_SPI1_DR);
- fifobytes--;
+ rxpending--;
}
}
}
diff --git a/nuttx/configs/mcu123-lpc214x/usbserial/defconfig b/nuttx/configs/mcu123-lpc214x/usbserial/defconfig
index a9a41bfad..445cbac4e 100644
--- a/nuttx/configs/mcu123-lpc214x/usbserial/defconfig
+++ b/nuttx/configs/mcu123-lpc214x/usbserial/defconfig
@@ -308,8 +308,15 @@ CONFIG_FS_ROMFS=n
# Number of MMC/SD slots supported by the driver
# CONFIG_MMCSD_READONLY
# Provide read-only access (default is read/write)
+# CONFIG_MMCSD_SPICLOCK - Maximum SPI clock to drive MMC/SD card.
+# Default is 20MHz.
+# CONFIG_MMCSD_SYNCHRONIZE
+# Special synchronization logic needed
+#
CONFIG_MMCSD_NSLOTS=1
CONFIG_MMCSD_READONLY=n
+#CONFIG_MMCSD_SPICLOCK=20000000
+CONFIG_MMCSD_SYNCHRONIZE=y
#
# TCP/IP and UDP support via uIP
diff --git a/nuttx/configs/mcu123-lpc214x/usbstorage/defconfig b/nuttx/configs/mcu123-lpc214x/usbstorage/defconfig
index 170acc236..da601a98f 100644
--- a/nuttx/configs/mcu123-lpc214x/usbstorage/defconfig
+++ b/nuttx/configs/mcu123-lpc214x/usbstorage/defconfig
@@ -308,8 +308,15 @@ CONFIG_FS_ROMFS=n
# Number of MMC/SD slots supported by the driver
# CONFIG_MMCSD_READONLY
# Provide read-only access (default is read/write)
+# CONFIG_MMCSD_SPICLOCK - Maximum SPI clock to drive MMC/SD card.
+# Default is 20MHz.
+# CONFIG_MMCSD_SYNCHRONIZE
+# Special synchronization logic needed
+#
CONFIG_MMCSD_NSLOTS=1
CONFIG_MMCSD_READONLY=n
+#CONFIG_MMCSD_SPICLOCK=20000000
+CONFIG_MMCSD_SYNCHRONIZE=y
#
# TCP/IP and UDP support via uIP
diff --git a/nuttx/drivers/mmcsd/mmcsd_spi.c b/nuttx/drivers/mmcsd/mmcsd_spi.c
index 637ec2e04..06b660a2f 100644
--- a/nuttx/drivers/mmcsd/mmcsd_spi.c
+++ b/nuttx/drivers/mmcsd/mmcsd_spi.c
@@ -168,6 +168,9 @@ static void mmcsd_semtake(sem_t *sem);
/* Card SPI interface *******************************************************/
+#ifdef CONFIG_MMCSD_SYNCHRONIZE
+static inline void mmcsd_synchronize(FAR struct mmcsd_slot_s *slot);
+#endif
static int mmcsd_waitready(FAR struct mmcsd_slot_s *slot);
static uint32 mmcsd_sendcmd(FAR struct mmcsd_slot_s *slot,
const struct mmcsd_cmdinfo_s *cmd, uint32 arg);
@@ -344,6 +347,38 @@ static void mmcsd_semtake(sem_t *sem)
#define mmcsd_semgive(sem) sem_post(sem)
/****************************************************************************
+ * Name: mmcsd_synchronize
+ *
+ * Description:
+ * Wait until the the card is no longer busy
+ *
+ * Assumptions:
+ * MMC/SD card already selected
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_MMCSD_SYNCHRONIZE
+static inline void mmcsd_synchronize(FAR struct mmcsd_slot_s *slot)
+{
+ FAR struct spi_dev_s *spi = slot->spi;
+
+ /* De-select the MMCSD card */
+
+ SPI_SELECT(spi, SPIDEV_MMCSD, FALSE);
+
+ /* Wait a bit */
+
+ SPI_SEND(spi, 0xff);
+
+ /* Reselect the card */
+
+ SPI_SELECT(spi, SPIDEV_MMCSD, TRUE);
+}
+#else
+# define mmcsd_synchronize(slot) /* No synchronization needed */s
+#endif
+
+/****************************************************************************
* Name: mmcsd_waitready
*
* Description:
@@ -625,7 +660,7 @@ static void mmcsd_decodecsd(FAR struct mmcsd_slot_s *slot, ubyte *csd)
g_transpeedru[MMCSD_CSD_TRANSPEED_TRANSFERRATEUNIT(csd)];
/* Clip the max frequency to account for board limitations */
-
+
frequency = maxfrequency;
if (frequency > CONFIG_MMCSD_SPICLOCK)
{
@@ -804,6 +839,7 @@ static int mmcsd_getcardinfo(FAR struct mmcsd_slot_s *slot, ubyte *buffer,
/* Send the CMD9 or CMD10 */
+ mmcsd_synchronize(slot);
result = mmcsd_sendcmd(slot, cmd, 0);
if (result != MMCSD_SPIR1_OK)
{
@@ -1081,7 +1117,7 @@ static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer,
mmcsd_semtake(&slot->sem);
SPI_SELECT(spi, SPIDEV_MMCSD, TRUE);
- SPI_SEND(spi, 0xff);
+ mmcsd_synchronize(slot);
/* Single or multiple block read? */
@@ -1108,7 +1144,7 @@ static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer,
}
else
{
- /* Send CMD17: Reads a block of the size selected by the SET_BLOCKLEN
+ /* Send CMD18: Reads a block of the size selected by the SET_BLOCKLEN
* command and verify that good R1 status is returned
*/
@@ -1243,7 +1279,7 @@ static ssize_t mmcsd_write(FAR struct inode *inode, const unsigned char *buffer,
mmcsd_semtake(&slot->sem);
SPI_SELECT(spi, SPIDEV_MMCSD, TRUE);
- SPI_SEND(spi, 0xff);
+ mmcsd_synchronize(slot);
/* Single or multiple block transfer? */
@@ -1533,9 +1569,11 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot)
do
{
fvdbg("%d. Send CMD55/ACMD41\n", elapsed);
+ mmcsd_synchronize(slot);
result = mmcsd_sendcmd(slot, &g_cmd55, 0);
if (result == MMCSD_SPIR1_IDLESTATE || result == MMCSD_SPIR1_OK)
{
+ mmcsd_synchronize(slot);
result = mmcsd_sendcmd(slot, &g_acmd41, 1 << 30);
if (result == MMCSD_SPIR1_OK)
{
@@ -1578,11 +1616,13 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot)
/* Both the MMC card and the SD card support CMD55 */
fvdbg("Send CMD55/ACMD41\n");
+ mmcsd_synchronize(slot);
result = mmcsd_sendcmd(slot, &g_cmd55, 0);
if (result == MMCSD_SPIR1_IDLESTATE || result == MMCSD_SPIR1_OK)
{
/* But ACMD41 is supported only on SD */
+ mmcsd_synchronize(slot);
result = mmcsd_sendcmd(slot, &g_acmd41, 0);
if (result == MMCSD_SPIR1_IDLESTATE || result == MMCSD_SPIR1_OK)
{
@@ -1600,9 +1640,11 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot)
if (IS_SD(slot->type))
{
fvdbg("%d. Send CMD55/ACMD41\n", elapsed);
+ mmcsd_synchronize(slot);
result = mmcsd_sendcmd(slot, &g_cmd55, 0);
if (result == MMCSD_SPIR1_IDLESTATE || result == MMCSD_SPIR1_OK)
{
+ mmcsd_synchronize(slot);
result = mmcsd_sendcmd(slot, &g_acmd41, 0);
if (result == MMCSD_SPIR1_OK)
{
@@ -1613,6 +1655,7 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot)
else
{
fvdbg("%d. Send CMD1\n", i);
+ mmcsd_synchronize(slot);
result = mmcsd_sendcmd(slot, &g_cmd1, 0);
if (result == MMCSD_SPIR1_OK)
{