Skip to content

Commit

Permalink
backport SDIO Fix - no busy waiting
Browse files Browse the repository at this point in the history
  • Loading branch information
David Sidrane committed Jan 8, 2015
1 parent 255dc96 commit dbcccb2
Show file tree
Hide file tree
Showing 4 changed files with 125 additions and 9 deletions.
79 changes: 78 additions & 1 deletion nuttx/arch/arm/src/stm32/stm32_sdio.c
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -399,6 +399,9 @@ static void stm32_endtransfer(struct stm32_dev_s *priv, sdio_eventset_t wkupeven
/* Interrupt Handling *******************************************************/

static int stm32_interrupt(int irq, void *context);
#ifdef CONFIG_MMCSD_HAVE_SDIOWAIT_WRCOMPLETE
static int stm32_rdyinterrupt(int irq, void *context);
#endif

/* SDIO interface methods ***************************************************/

Expand Down Expand Up @@ -611,12 +614,40 @@ static void stm32_configwaitints(struct stm32_dev_s *priv, uint32_t waitmask,
sdio_eventset_t wkupevent)
{
irqstate_t flags;
#ifdef CONFIG_MMCSD_HAVE_SDIOWAIT_WRCOMPLETE
int pinset;
#endif

/* Save all of the data and set the new interrupt mask in one, atomic
* operation.
*/

flags = irqsave();

#ifdef CONFIG_MMCSD_HAVE_SDIOWAIT_WRCOMPLETE
if ((waitmask & SDIOWAIT_WRCOMPLETE) != 0)
{

/* Do not use this in STM32_SDIO_MASK register */

waitmask &= !SDIOWAIT_WRCOMPLETE;

pinset = GPIO_SDIO_D0 & (GPIO_PORT_MASK|GPIO_PIN_MASK);
pinset |= (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI);

/* Arm the SDIO_D Ready and install Isr */

stm32_gpiosetevent(pinset, true, false, false, stm32_rdyinterrupt);
}

/* Disarm SDIO_D ready */

if ((wkupevent & SDIOWAIT_WRCOMPLETE) != 0)
{
stm32_gpiosetevent(GPIO_SDIO_D0, false, false, false , NULL);
stm32_configgpio(GPIO_SDIO_D0);

}
#endif
priv->waitevents = waitevents;
priv->wkupevent = wkupevent;
priv->waitmask = waitmask;
Expand Down Expand Up @@ -1229,7 +1260,28 @@ static void stm32_endtransfer(struct stm32_dev_s *priv, sdio_eventset_t wkupeven
/****************************************************************************
* Interrrupt Handling
****************************************************************************/
#ifdef CONFIG_MMCSD_HAVE_SDIOWAIT_WRCOMPLETE
/****************************************************************************
* Name: stm32_rdyinterrupt
*
* Description:
* SDIO ready interrupt handler
*
* Input Parameters:
* dev - An instance of the SDIO device interface
*
* Returned Value:
* None
*
****************************************************************************/

static int stm32_rdyinterrupt(int irq, void *context)
{
struct stm32_dev_s *priv = &g_sdiodev;
stm32_endwait(priv, SDIOWAIT_WRCOMPLETE);
return OK;
}
#endif
/****************************************************************************
* Name: stm32_interrupt
*
Expand Down Expand Up @@ -2228,6 +2280,14 @@ static void stm32_waitenable(FAR struct sdio_dev_s *dev,
* interrupts.
*/

#if defined(CONFIG_MMCSD_HAVE_SDIOWAIT_WRCOMPLETE)
if ((eventset & SDIOWAIT_WRCOMPLETE) != 0)
{
waitmask = SDIOWAIT_WRCOMPLETE;
}
else
{
#endif
waitmask = 0;
if ((eventset & SDIOWAIT_CMDDONE) != 0)
{
Expand All @@ -2247,6 +2307,9 @@ static void stm32_waitenable(FAR struct sdio_dev_s *dev,
/* Enable event-related interrupts */

putreg32(SDIO_WAITALL_ICR, STM32_SDIO_ICR);
#if defined(CONFIG_MMCSD_HAVE_SDIOWAIT_WRCOMPLETE)
}
#endif
stm32_configwaitints(priv, waitmask, eventset, 0);
}

Expand Down Expand Up @@ -2316,6 +2379,20 @@ static sdio_eventset_t stm32_eventwait(FAR struct sdio_dev_s *dev,
}
}

#if defined(CONFIG_MMCSD_HAVE_SDIOWAIT_WRCOMPLETE)
if ((priv->waitevents & SDIOWAIT_WRCOMPLETE) != 0)
{

/* Atomically read pin to see if ready (true) and determine if ISR fired
* If Pin is ready and if ISR did NOT fire end the wait here
*/

if (stm32_gpioread(GPIO_SDIO_D0) && ((priv->wkupevent & SDIOWAIT_WRCOMPLETE) == 0))
{
stm32_endwait(priv, SDIOWAIT_WRCOMPLETE);
}
}
#endif
/* Loop until the event (or the timeout occurs). Race conditions are avoided
* by calling stm32_waitenable prior to triggering the logic that will cause
* the wait to terminate. Under certain race conditions, the waited-for
Expand Down
26 changes: 21 additions & 5 deletions nuttx/drivers/mmcsd/Kconfig
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -32,11 +32,27 @@ config MMCSD_MMCSUPPORT
Enable support for MMC cards

config MMCSD_HAVECARDDETECT
bool "MMC/SD card detection"
default y
---help---
SDIO driver card detection is
100% accurate
bool "MMC/SD card detection"
default y
---help---
SDIO driver card detection is
100% accurate

config MMCSD_HAVE_SDIOWAIT_WRCOMPLETE
bool "Use SDIO_D Busy to detect Write Complete"
default n
---help---
SDIO driver will use SDIO_D Busy signaling to detect Write Complete.
This option when selected, will enable the MMCSD driver to use the
underlying (stm32_sdio only) drivers implementation of the SD specs
SDIO_D Busy signaling to detect Write Complete. This will avoid
potentially very long (600Ms+) busy waiting in the MMCSD driver.
To implement SDIO_D Busy signaling, the underlying driver must
be capable of switching the GPIO_SDIO_D0 to be a rising edge sensitive
interrupt pin. It must then, condition that pin to detect the rising edge
on recipet of SDWAIT_WRCOMPLETE in the SDIO_WAITENABLE call and
return it back to regular SDIO mode, when either the ISR fires or pin is
found to be high in the SDIO_EVENTWAIT call.

config MMCSD_SPI
bool "MMC/SD SPI transfer support"
Expand Down
20 changes: 20 additions & 0 deletions nuttx/drivers/mmcsd/mmcsd_sdio.c
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,9 @@
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#if !defined(MMCSD_BLOCK_WDATADELAY)
# define MMCSD_BLOCK_WDATADELAY 200
#endif

/* The maximum number of references on the driver (because a uint8_t is used.
* Use a larger type if more references are needed.
Expand Down Expand Up @@ -1142,6 +1145,15 @@ static int mmcsd_transferready(FAR struct mmcsd_state_s *priv)
* the TRANSFER state when the card completes the WRITE operation.
*/

#if defined(CONFIG_MMCSD_HAVE_SDIOWAIT_WRCOMPLETE)
ret = mmcsd_eventwait(priv, SDIOWAIT_TIMEOUT|SDIOWAIT_ERROR, MMCSD_BLOCK_WDATADELAY);

if (ret != OK)
{
fdbg("ERROR: mmcsd_eventwait for transferready failed: %d\n", ret);
}
#endif

starttime = clock_systimer();
do
{
Expand Down Expand Up @@ -1707,6 +1719,14 @@ static ssize_t mmcsd_writesingle(FAR struct mmcsd_state_s *priv,
return ret;
}

#if defined(CONFIG_MMCSD_HAVE_SDIOWAIT_WRCOMPLETE)

/* Arm the write complete detection with timeout */

SDIO_WAITENABLE(priv->dev, SDIOWAIT_WRCOMPLETE|SDIOWAIT_TIMEOUT);

#endif

/* On success, return the number of blocks written */

return 1;
Expand Down
9 changes: 6 additions & 3 deletions nuttx/include/nuttx/sdio.h
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -62,9 +62,12 @@
#define SDIOWAIT_TRANSFERDONE (1 << 2) /* Bit 2: Data transfer/DMA done */
#define SDIOWAIT_TIMEOUT (1 << 3) /* Bit 3: Timeout */
#define SDIOWAIT_ERROR (1 << 4) /* Bit 4: Some other error occurred */

#define SDIOWAIT_ALLEVENTS 0x1f

#if defined(CONFIG_MMCSD_HAVE_SDIOWAIT_WRCOMPLETE)
#define SDIOWAIT_WRCOMPLETE (1 << 5) /* Bit 5: Hardware Write Completion */
# define SDIOWAIT_ALLEVENTS 0x3f
#else
# define SDIOWAIT_ALLEVENTS 0x1f
#endif
/* Media events are used for enable/disable registered event callbacks */

#define SDIOMEDIA_EJECTED (1 << 0) /* Bit 0: Mmedia removed */
Expand Down

0 comments on commit dbcccb2

Please sign in to comment.