From 5bf07f207c79d01d0c07245ab4c0d76f8ed9567a Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 17 Nov 2009 21:31:56 +0000 Subject: Code complete for STM32 SDIO driver and MMC/SD SDIO driver git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2266 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/stm32/stm32_dma.c | 4 +- nuttx/arch/arm/src/stm32/stm32_internal.h | 56 +++++ nuttx/arch/arm/src/stm32/stm32_sdio.c | 363 +++++++++++++++++++++++------- nuttx/configs/stm3210e-eval/src/up_nsh.c | 76 +++++-- nuttx/drivers/mmcsd/mmcsd_sdio.c | 155 +++++++++---- nuttx/include/nuttx/mmcsd.h | 5 +- nuttx/include/nuttx/sdio.h | 41 ++-- 7 files changed, 528 insertions(+), 172 deletions(-) diff --git a/nuttx/arch/arm/src/stm32/stm32_dma.c b/nuttx/arch/arm/src/stm32/stm32_dma.c index adf651236..320d3a558 100755 --- a/nuttx/arch/arm/src/stm32/stm32_dma.c +++ b/nuttx/arch/arm/src/stm32/stm32_dma.c @@ -414,7 +414,7 @@ void stm32_dmasetup(DMA_HANDLE handle, uint32 paddr, uint32 maddr, size_t ntrans * half and/or full transfer in the DMA_CCRx register. */ - regval = dmachan_gettreg(dmach, STM32_DMACHAN_CCR_OFFSET); + regval = dmachan_getreg(dmach, STM32_DMACHAN_CCR_OFFSET); regval &= ~(DMA_CCR_MEM2MEM|DMA_CCR_PL_MASK|DMA_CCR_MSIZE_MASK|DMA_CCR_PSIZE_MASK| DMA_CCR_MINC|DMA_CCR_PINC|DMA_CCR_CIRC|DMA_CCR_DIR); ccr &= (DMA_CCR_MEM2MEM|DMA_CCR_PL_MASK|DMA_CCR_MSIZE_MASK|DMA_CCR_PSIZE_MASK| @@ -453,7 +453,7 @@ void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg, boole * peripheral connected on the channel. */ - ccr = dmachan_gettreg(dmach, STM32_DMACHAN_CCR_OFFSET); + ccr = dmachan_getreg(dmach, STM32_DMACHAN_CCR_OFFSET); ccr |= DMA_CCR_EN; /* Once half of the bytes are transferred, the half-transfer flag (HTIF) is diff --git a/nuttx/arch/arm/src/stm32/stm32_internal.h b/nuttx/arch/arm/src/stm32/stm32_internal.h index 108e9b0a5..9964c1130 100755 --- a/nuttx/arch/arm/src/stm32/stm32_internal.h +++ b/nuttx/arch/arm/src/stm32/stm32_internal.h @@ -445,6 +445,62 @@ EXTERN int stm32_usbpullup(FAR struct usbdev_s *dev, boolean enable); struct usbdev_s; EXTERN void stm32_usbsuspend(FAR struct usbdev_s *dev, boolean resume); +/**************************************************************************** + * Name: sdio_initialize + * + * Description: + * Initialize SDIO for operation. + * + * Input Parameters: + * slotno - Not used. + * + * Returned Values: + * A reference to an SDIO interface structure. NULL is returned on failures. + * + ****************************************************************************/ + +struct sdio_dev_s; /* See include/nuttx/sdio.h */ +EXTERN FAR struct sdio_dev_s *sdio_initialize(int slotno); + +/**************************************************************************** + * Name: sdio_mediachange + * + * Description: + * Called by board-specific logic -- posssible from an interrupt handler -- + * in order to signal to the driver that a card has been inserted or + * removed from the slot + * + * Input Parameters: + * dev - An instance of the SDIO driver device state structure. + * cardinslot - TRUE is a card has been detected in the slot; FALSE if a + * card has been removed from the slot. Only transitions + * (inserted->removed or removed->inserted should be reported) + * + * Returned Values: + * None + * + ****************************************************************************/ + +EXTERN void sdio_mediachange(FAR struct sdio_dev_s *dev, boolean cardinslot); + +/**************************************************************************** + * Name: sdio_wrprotect + * + * Description: + * Called by board-specific logic to report if the card in the slot is + * mechanically write protected. + * + * Input Parameters: + * dev - An instance of the SDIO driver device state structure. + * wrprotect - TRUE is a card is writeprotected. + * + * Returned Values: + * None + * + ****************************************************************************/ + +EXTERN void sdio_wrprotect(FAR struct sdio_dev_s *dev, boolean wrprotect); + #undef EXTERN #if defined(__cplusplus) } diff --git a/nuttx/arch/arm/src/stm32/stm32_sdio.c b/nuttx/arch/arm/src/stm32/stm32_sdio.c index bedada379..f76b55988 100644 --- a/nuttx/arch/arm/src/stm32/stm32_sdio.c +++ b/nuttx/arch/arm/src/stm32/stm32_sdio.c @@ -42,12 +42,14 @@ #include #include -#include +#include +#include #include -#include -#include +#include #include +#include +#include #include #include "chip.h" @@ -85,15 +87,21 @@ /* HCLK=72MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(178+2)=400 KHz */ #define SDIO_INIT_CLKDIV (178 << SDIO_CLKCR_CLKDIV_SHIFT) -#define STM32_CLCKCR_INIT \ - (SDIO_INIT_CLKDIV|SDIO_CLKCR_RISINGEDGE|SDIO_CLKCR_WIDBUS_D1) +#define STM32_CLCKCR_INIT (SDIO_INIT_CLKDIV|SDIO_CLKCR_RISINGEDGE|\ + SDIO_CLKCR_WIDBUS_D1) +/* HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(2+2)=18 MHz */ + +#define SDIO_MMCXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT) +#define SDIO_CLKCR_MMCXFR (SDIO_SDXFR_CLKDIV|SDIO_CLKCR_RISINGEDGE|\ + SDIO_CLKCR_WIDBUS_D1) + /* HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(1+2)=24 MHz */ -#define SDIO_TRANSFER_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT) -#define STM32_CLCKCR_TRANSFER (SDIO_TRANSFER_CLKDIV|SDIO_CLKCR_RISINGEDGE|\ +#define SDIO_SDXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT) +#define SDIO_CLCKR_SDXFR (SDIO_SDXFR_CLKDIV|SDIO_CLKCR_RISINGEDGE|\ SDIO_CLKCR_WIDBUS_D1) -#define STM32_CLKCR_WIDETRANSFER (SDIO_TRANSFER_CLKDIV|SDIO_CLKCR_RISINGEDGE|\ +#define SDIO_CLCKR_SDWIDEXFR (SDIO_SDXFR_CLKDIV|SDIO_CLKCR_RISINGEDGE|\ SDIO_CLKCR_WIDBUS_D4) /* Timing */ @@ -164,11 +172,17 @@ struct stm32_dev_s struct sdio_dev_s dev; /* Standard, base SDIO interface */ /* STM32-specific extensions */ + /* Event support */ sem_t waitsem; /* Implements event waiting */ sdio_eventset_t waitevents; /* Set of events to be waited for */ uint32 waitmask; /* Interrupt enables for event waiting */ volatile sdio_eventset_t wkupevent; /* The event that caused the wakeup */ + WDOG_ID waitwdog; /* Watchdog that handles event timeouts */ + + /* Callback support */ + + ubyte cdstatus; /* Card status */ sdio_eventset_t cbevents; /* Set of events to be cause callbacks */ sdio_mediachange_t callback; /* Registered callback function */ void *cbarg; /* Registered callback argument */ @@ -199,12 +213,10 @@ static void stm32_takesem(struct stm32_dev_s *priv); #define stm32_givesem(priv) (sem_post(&priv->waitsem)) static inline void stm32_setclkcr(uint32 clkcr); static void stm32_configwaitints(struct stm32_dev_s *priv, uint32 waitmask, - ubyte waitevents, ubyte wkupevents); + sdio_eventset_t waitevents, sdio_eventset_t wkupevents); static void stm32_configxfrints(struct stm32_dev_s *priv, uint32 xfrmask); static void stm32_setpwrctrl(uint32 pwrctrl); static inline uint32 stm32_getpwrctrl(void); -static inline void stm32_clkenable(void); -static inline void stm32_clkdisable(void); /* DMA Helpers **************************************************************/ @@ -219,7 +231,8 @@ static void stm32_dataconfig(uint32 timeout, uint32 dlen, uint32 dctrl); static void stm32_datadisable(void); static void stm32_sendfifo(struct stm32_dev_s *priv); static void stm32_recvfifo(struct stm32_dev_s *priv); -static void stm32_endwait(struct stm32_dev_s *priv, uint32 eventset); +static void stm32_eventtimeout(int argc, uint32 arg); +static void stm32_endwait(struct stm32_dev_s *priv, sdio_eventset_t wkupevent); static void stm32_endtransfer(struct stm32_dev_s *priv, int result); /* Interrupt Handling *******************************************************/ @@ -260,8 +273,8 @@ static int stm32_recvnotimpl(FAR struct sdio_dev_s *dev, uint32 cmd, static void stm32_waitenable(FAR struct sdio_dev_s *dev, sdio_eventset_t eventset); -static ubyte stm32_eventwait(FAR struct sdio_dev_s *dev, uint32 timeout); -static ubyte stm32_events(FAR struct sdio_dev_s *dev); +static sdio_eventset_t + stm32_eventwait(FAR struct sdio_dev_s *dev, uint32 timeout); static void stm32_callbackenable(FAR struct sdio_dev_s *dev, sdio_eventset_t eventset); static int stm32_registercallback(FAR struct sdio_dev_s *dev, @@ -308,7 +321,6 @@ struct stm32_dev_s g_sdiodev = .recvR7 = stm32_recvshort, .waitenable = stm32_waitenable, .eventwait = stm32_eventwait, - .events = stm32_events, .callbackenable = stm32_callbackenable, .registercallback = stm32_registercallback, #ifdef CONFIG_SDIO_DMA @@ -397,10 +409,10 @@ static inline void stm32_setclkcr(uint32 clkcr) * Enable/disable SDIO interrupts needed to suport the wait function * * Input Parameters: - * priv - A reference to the SDIO device state structure - * waitmask - The set of bits in the SDIO MASK register to set - * waitevent - Waited for events - * wkupevent - Wake-up events + * priv - A reference to the SDIO device state structure + * waitmask - The set of bits in the SDIO MASK register to set + * waitevents - Waited for events + * wkupevent - Wake-up events * * Returned Value: * None @@ -408,7 +420,8 @@ static inline void stm32_setclkcr(uint32 clkcr) ****************************************************************************/ static void stm32_configwaitints(struct stm32_dev_s *priv, uint32 waitmask, - ubyte waitevents, ubyte wkupevent) + sdio_eventset_t waitevents, + sdio_eventset_t wkupevent) { irqstate_t flags; flags = irqsave(); @@ -489,16 +502,6 @@ static inline uint32 stm32_getpwrctrl(void) return getreg32(STM32_SDIO_POWER) & SDIO_POWER_PWRCTRL_MASK; } -static inline void stm32_clkenable(void) -{ - putreg32(1, SDIO_CLKCR_CLKEN_BB); -} - -static inline void stm32_clkdisable(void) -{ - putreg32(0, SDIO_CLKCR_CLKEN_BB); -} - /**************************************************************************** * DMA Helpers ****************************************************************************/ @@ -730,6 +733,42 @@ static void stm32_recvfifo(struct stm32_dev_s *priv) } } +/**************************************************************************** + * Name: stm32_eventtimeout + * + * Description: + * The watchdog timeout setup when the event wait start has expired without + * any other waited-for event occurring. + * + * Input Parameters: + * argc - The number of arguments (should be 1) + * arg - The argument (state structure reference cast to uint32) + * + * Returned Value: + * None + * + * Assumptions: + * Always called from the interrupt level with interrupts disabled. + * + ****************************************************************************/ + +static void stm32_eventtimeout(int argc, uint32 arg) +{ + struct stm32_dev_s *priv = (struct stm32_dev_s *)arg; + + DEBUGASSERT(argc == 1 && priv != NULL); + DEBUGASSERT((priv->waitevents & SDIOWAIT_TIMEOUT) != 0); + + /* Is a data transfer complete event expected? */ + + if ((priv->waitevents & SDIOWAIT_TIMEOUT) != 0) + { + /* Yes.. wake up any waiting threads */ + + stm32_endwait(priv, SDIOWAIT_TIMEOUT); + } +} + /**************************************************************************** * Name: stm32_endwait * @@ -743,13 +782,20 @@ static void stm32_recvfifo(struct stm32_dev_s *priv) * Returned Value: * None * + * Assumptions: + * Always called from the interrupt level with interrupts disabled. + * ****************************************************************************/ -static void stm32_endwait(struct stm32_dev_s *priv, uint32 eventset) +static void stm32_endwait(struct stm32_dev_s *priv, sdio_eventset_t wkupevent) { - /* Yes.. Disable event-related interrupts */ + /* Cancel the watchdog timeout */ + + (void)wd_cancel(priv->waitwdog); - stm32_configwaitints(priv, 0, 0, eventset); + /* Disable event-related interrupts */ + + stm32_configwaitints(priv, 0, 0, wkupevent); /* Wake up the waiting thread */ @@ -767,7 +813,10 @@ static void stm32_endwait(struct stm32_dev_s *priv, uint32 eventset) * result - The result status of the transfer * * Returned Value: - * None + * None + * + * Assumptions: + * Always called from the interrupt level with interrupts disabled. * ****************************************************************************/ @@ -991,7 +1040,49 @@ static int stm32_interrupt(int irq, void *context) ****************************************************************************/ static void stm32_reset(FAR struct sdio_dev_s *dev) -{ +{ + FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev; + irqstate_t flags; + + /* Disable clocking */ + + flags = irqsave(); + putreg32(0, SDIO_CLKCR_CLKEN_BB); + stm32_setpwrctrl(SDIO_POWER_PWRCTRL_OFF); + + /* Put SDIO registers in their default, reset state */ + + stm32_default(); + + /* Reset data */ + + priv->waitevents = 0; /* Set of events to be waited for */ + priv->waitmask = 0; /* Interrupt enables for event waiting */ + priv->wkupevent = 0; /* The event that caused the wakeup */ + wd_cancel(priv->waitwdog); /* Cancel any timeouts */ + + /* Interrupt mode data transfer support */ + + priv->buffer = 0; /* Address of current R/W buffer */ + priv->remaining = 0; /* Number of bytes remaining in the transfer */ + priv->result = 0; /* Result of the transfer */ + priv->xfrmask = 0; /* Interrupt enables for data transfer */ + + /* DMA data transfer support */ + + priv->widebus = FALSE; /* Required for DMA support */ +#ifdef CONFIG_SDIO_DMA + priv->dmamode = FALSE; /* TRUE: DMA mode transfer */ +#endif + + /* Configure the SDIO peripheral */ + + stm32_setclkcr(STM32_CLCKCR_INIT); + stm32_setpwrctrl(SDIO_POWER_PWRCTRL_ON); + + /* (Re-)enable clocking */ + + putreg32(1, SDIO_CLKCR_CLKEN_BB); } /**************************************************************************** @@ -1009,8 +1100,9 @@ static void stm32_reset(FAR struct sdio_dev_s *dev) ****************************************************************************/ static ubyte stm32_status(FAR struct sdio_dev_s *dev) -{ - return 0; +{ + struct stm32_dev_s *priv = (struct stm32_dev_s *)dev; + return priv->cdstatus; } /**************************************************************************** @@ -1052,8 +1144,38 @@ static void stm32_widebus(FAR struct sdio_dev_s *dev, boolean wide) ****************************************************************************/ static void stm32_clock(FAR struct sdio_dev_s *dev, enum sdio_clock_e rate) -{ -} +{ + uint32 clckr; + + switch (rate) + { + case CLOCK_SDIO_DISABLED: /* Clock is disabled */ + putreg32(0, SDIO_CLKCR_CLKEN_BB); + break; + + default: + case CLOCK_IDMODE: /* Initial ID mode clocking (<400KHz) */ + clckr = STM32_CLCKCR_INIT; + break; + + case CLOCK_MMC_TRANSFER: /* MMC normal operation clocking */ + clckr = SDIO_CLKCR_MMCXFR; + break; + + case CLOCK_SD_TRANSFER_1BIT: /* SD normal operation clocking (narrow 1-bit mode) */ + clckr = SDIO_CLCKR_SDXFR; + break; + + case CLOCK_SD_TRANSFER_4BIT: /* SD normal operation clocking (wide 4-bit mode) */ + clckr = SDIO_CLCKR_SDWIDEXFR; + break; + }; + + /* Set the new clock frequency and make sure that the clock is enabled */ + + stm32_setclkcr(STM32_CLCKCR_INIT); + putreg32(1, SDIO_CLKCR_CLKEN_BB); +} /**************************************************************************** * Name: stm32_attach @@ -1559,7 +1681,7 @@ static int stm32_recvnotimpl(FAR struct sdio_dev_s *dev, uint32 cmd, uint32 *rno * Description: * Enable/disable of a set of SDIO wait events. This is part of the * the SDIO_WAITEVENT sequence. The set of to-be-waited-for events is - * configured before calling stm32_waitevent. This is done in this way + * configured before calling stm32_eventwait. This is done in this way * to help the driver to eliminate race conditions between the command * setup and the subsequent events. * @@ -1626,28 +1748,55 @@ static void stm32_waitenable(FAR struct sdio_dev_s *dev, * * Input Parameters: * dev - An instance of the SDIO device interface - * timeout - Maximum time in milliseconds to wait. Zero means no timeout. + * timeout - Maximum time in milliseconds to wait. Zero means immediate + * timeout with no wait. The timeout value is ignored if + * SDIOWAIT_TIMEOUT is not included in the waited-for eventset. * * Returned Value: - * Event set containing the event(s) that ended the wait. If no events the - * returned event set is zero, then the wait was terminated by the timeout. - * All events are cleared disabled after the wait concludes. + * Event set containing the event(s) that ended the wait. Should always + * be non-zero. All events are disabled after the wait concludes. * ****************************************************************************/ -static ubyte stm32_eventwait(FAR struct sdio_dev_s *dev, uint32 timeout) +static sdio_eventset_t stm32_eventwait(FAR struct sdio_dev_s *dev, + uint32 timeout) { struct stm32_dev_s *priv = (struct stm32_dev_s*)dev; - ubyte wkupevent = 0; + sdio_eventset_t wkupevent = 0; + int ret; DEBUGASSERT(priv->waitevents != 0); + /* Check if the timeout event is specified in the event set */ + + if ((priv->waitevents & SDIOWAIT_TIMEOUT) != 0) + { + int delay; + + /* Yes.. Handle a cornercase */ + + if (!timeout) + { + return SDIOWAIT_TIMEOUT; + } + + /* Start the watchdog timer */ + + delay = (timeout + (MSEC_PER_TICK-1)) / MSEC_PER_TICK; + ret = wd_start(priv->waitwdog, delay, (wdentry_t)stm32_eventtimeout, + 1, (uint32)priv); + if (ret != OK) + { + fdbg("ERROR: wd_start failed: %d\n", ret); + } + } + /* 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 * may have already occurred before this function was called! */ -#warning "Timeout logic not implemented" + for (;;) { /* Wait for an event in event set to occur. If this the event has already @@ -1674,27 +1823,6 @@ static ubyte stm32_eventwait(FAR struct sdio_dev_s *dev, uint32 timeout) return wkupevent; } -/**************************************************************************** - * Name: stm32_events - * - * Description: - * Return the current event set. This supports polling for SDIO (vs. - * waiting). Only enabled events need be reported. - * - * Input Parameters: - * dev - An instance of the SDIO device interface - * - * Returned Value: - * Event set containing the current events (All pending events are cleared - * after reading). - * - ****************************************************************************/ - -static ubyte stm32_events(FAR struct sdio_dev_s *dev) -{ - return 0; -} - /**************************************************************************** * Name: stm32_callbackenable * @@ -1975,7 +2103,6 @@ static void stm32_callback(void *arg) priv->cbevents = 0; priv->callback(priv->cbarg); - } } @@ -2020,13 +2147,15 @@ static void stm32_default(void) FAR struct sdio_dev_s *sdio_initialize(int slotno) { - /* There is only one, slot */ + /* There is only one slot */ struct stm32_dev_s *priv = &g_sdiodev; /* Initialize the SDIO slot structure */ sem_init(&priv->waitsem, 0, 0); + priv->waitwdog = wd_create(); + DEBUGASSERT(priv->waitwdog); /* Allocate a DMA channel */ @@ -2043,19 +2172,95 @@ FAR struct sdio_dev_s *sdio_initialize(int slotno) stm32_configgpio(GPIO_SDIO_D2); stm32_configgpio(GPIO_SDIO_D3); stm32_configgpio(GPIO_SDIO_CK); - stm32_configgpio(GPIO_SDIO_CMD); + stm32_configgpio(GPIO_SDIO_CMD); + + /* Reset the card and assure that it is in the initial, unconfigured + * state. + */ + + stm32_reset(&priv->dev); + return &g_sdiodev.dev; +} - /* Put SDIO registers in their default, reset state */ +/**************************************************************************** + * Name: sdio_mediachange + * + * Description: + * Called by board-specific logic -- posssible from an interrupt handler -- + * in order to signal to the driver that a card has been inserted or + * removed from the slot + * + * Input Parameters: + * dev - An instance of the SDIO driver device state structure. + * cardinslot - TRUE is a card has been detected in the slot; FALSE if a + * card has been removed from the slot. Only transitions + * (inserted->removed or removed->inserted should be reported) + * + * Returned Values: + * None + * + ****************************************************************************/ - stm32_default(); +void sdio_mediachange(FAR struct sdio_dev_s *dev, boolean cardinslot) +{ + struct stm32_dev_s *priv = (struct stm32_dev_s *)dev; + ubyte cdstatus; + irqstate_t flags; - /* Configure the SDIO peripheral */ - - stm32_setclkcr(STM32_CLCKCR_INIT); - stm32_setpwrctrl(SDIO_POWER_PWRCTRL_ON); - stm32_clkenable(); + /* Update card status */ - return &g_sdiodev.dev; + flags = irqsave(); + cdstatus = priv->cdstatus; + if (cardinslot) + { + priv->cdstatus |= SDIO_STATUS_PRESENT; + } + else + { + priv->cdstatus &= ~SDIO_STATUS_PRESENT; + } + + /* Perform any requested callback if the status has changed */ + + if (cdstatus != priv->cdstatus) + { + stm32_callback(priv); + } + irqrestore(flags); } + +/**************************************************************************** + * Name: sdio_wrprotect + * + * Description: + * Called by board-specific logic to report if the card in the slot is + * mechanically write protected. + * + * Input Parameters: + * dev - An instance of the SDIO driver device state structure. + * wrprotect - TRUE is a card is writeprotected. + * + * Returned Values: + * None + * + ****************************************************************************/ +void sdio_wrprotect(FAR struct sdio_dev_s *dev, boolean wrprotect) +{ + struct stm32_dev_s *priv = (struct stm32_dev_s *)dev; + irqstate_t flags; + + /* Update card status */ + + flags = irqsave(); + if (wrprotect) + { + priv->cdstatus |= SDIO_STATUS_WRPROTECTED; + } + else + { + priv->cdstatus &= ~SDIO_STATUS_WRPROTECTED; + } + irqrestore(flags); +} #endif /* CONFIG_STM32_SDIO */ diff --git a/nuttx/configs/stm3210e-eval/src/up_nsh.c b/nuttx/configs/stm3210e-eval/src/up_nsh.c index 01dcb440b..4fde69626 100755 --- a/nuttx/configs/stm3210e-eval/src/up_nsh.c +++ b/nuttx/configs/stm3210e-eval/src/up_nsh.c @@ -49,7 +49,13 @@ # include # include #endif -#include + +#ifdef CONFIG_STM32_SDIO +# include +# include +#endif + +#include "stm32_internal.h" /**************************************************************************** * Pre-Processor Definitions @@ -63,20 +69,35 @@ /* PORT and SLOT number probably depend on the board configuration */ +#ifdef CONFIG_ARCH_BOARD_STM3210E_EVAL +# define CONFIG_EXAMPLES_NSH_HAVEUSBDEV 1 +# define CONFIG_EXAMPLES_NSH_HAVEMMCSD 1 +# if defined(CONFIG_EXAMPLES_NSH_MMCSDSLOTNO) && CONFIG_EXAMPLES_NSH_MMCSDSLOTNO != 0 +# error "Only one MMC/SD slot" +# undef CONFIG_EXAMPLES_NSH_MMCSDSLOTNO +# endif +# ifndef CONFIG_EXAMPLES_NSH_MMCSDSLOTNO +# define CONFIG_EXAMPLES_NSH_MMCSDSLOTNO 0 +# endif +#else + /* Add configuration for new STM32 boards here */ +# error "Unrecognized STM32 board" +# undef CONFIG_EXAMPLES_NSH_HAVEUSBDEV +# undef CONFIG_EXAMPLES_NSH_HAVEMMCSD +#endif + /* Can't support USB features if USB is not enabled */ #ifndef CONFIG_USBDEV # undef CONFIG_EXAMPLES_NSH_HAVEUSBDEV #endif -#if defined(CONFIG_EXAMPLES_NSH_MMCSDSLOTNO) && CONFIG_EXAMPLES_NSH_MMCSDSLOTNO != 0 -# error "Only one MMC/SD slot" -# undef CONFIG_EXAMPLES_NSH_MMCSDSLOTNO -#endif - -/* Can't support MMC/SD features if mountpoints are disabled */ +/* Can't support MMC/SD features if mountpoints are disabled or if SDIO support + * is not enabled. + */ -#if defined(CONFIG_DISABLE_MOUNTPOINT) +#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_STM32_SDIO) +#error OUCH # undef CONFIG_EXAMPLES_NSH_HAVEMMCSD #endif @@ -118,6 +139,10 @@ int nsh_archinitialize(void) FAR struct spi_dev_s *spi; FAR struct mtd_dev_s *mtd; #endif +#ifdef CONFIG_EXAMPLES_NSH_HAVEMMCSD + FAR struct sdio_dev_s *sdio; + int ret; +#endif /* Configure SPI-based devices */ @@ -147,13 +172,36 @@ int nsh_archinitialize(void) #endif /* Create the SPI FLASH MTD instance */ - - /* Here we will eventually need to - * 1. Get the SDIO interface instance, and - * 2. Bind it to the MMC/SD driver (slot CONFIG_EXAMPLES_NSH_MMCSDSLOTNO, - * CONFIG_EXAMPLES_NSH_MMCSDMINOR). + /* The M25Pxx is not a give media to implement a file system.. + * its block sizes are too large */ -#warning "Missing MMC/SD device configuration" + /* Mount the SDIO-based MMC/SD block driver */ + +#ifdef CONFIG_EXAMPLES_NSH_HAVEMMCSD + /* First, get an instance of the SDIO interface */ + + message("nsh_archinitialize: Initializing SDIO slot %d\n", + CONFIG_EXAMPLES_NSH_MMCSDSLOTNO); + sdio = sdio_initialize(CONFIG_EXAMPLES_NSH_MMCSDSLOTNO); + if (!sdio) + { + message("nsh_archinitialize: Failed to initialize SDIO slot %d\n", + CONFIG_EXAMPLES_NSH_MMCSDSLOTNO); + return -ENODEV; + } + + /* Now bind the SPI interface to the MMC/SD driver */ + + message("nsh_archinitialize: Bind SDIO to the MMC/SD driver, minor=%d\n", + CONFIG_EXAMPLES_NSH_MMCSDMINOR); + ret = mmcsd_slotinitialize(CONFIG_EXAMPLES_NSH_MMCSDMINOR, sdio); + if (ret != OK) + { + message("nsh_archinitialize: Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + return ret; + } + message("nsh_archinitialize: Successfully bound SDIO to the MMC/SD driver\n"); +#endif return OK; } diff --git a/nuttx/drivers/mmcsd/mmcsd_sdio.c b/nuttx/drivers/mmcsd/mmcsd_sdio.c index f64db9586..1a3016e88 100644 --- a/nuttx/drivers/mmcsd/mmcsd_sdio.c +++ b/nuttx/drivers/mmcsd/mmcsd_sdio.c @@ -161,11 +161,13 @@ static void mmcsd_decodeCID(FAR struct mmcsd_state_s *priv, uint32 cid[4]); static void mmcsd_decodeSCR(FAR struct mmcsd_state_s *priv, uint32 scr[2]); static int mmcsd_getR1(FAR struct mmcsd_state_s *priv, FAR uint32 *r1); -static int mmcsd_verifystandby(FAR struct mmcsd_state_s *priv); -static int mmcsd_verifyidle(FAR struct mmcsd_state_s *priv); +static int mmcsd_verifystate(FAR struct mmcsd_state_s *priv, uint32 status); /* Transfer helpers *********************************************************/ +static boolean mmcsd_wrprotected(FAR struct mmcsd_state_s *priv); +static int mmcsd_eventwait(FAR struct mmcsd_state_s *priv, + sdio_eventset_t failevents, uint32 timeout); static int mmcsd_transferready(FAR struct mmcsd_state_s *priv); static int mmcsd_stoptransmission(FAR struct mmcsd_state_s *priv); static int mmcsd_setblocklen(FAR struct mmcsd_state_s *priv, @@ -449,7 +451,7 @@ static int mmcsd_getSCR(FAR struct mmcsd_state_s *priv, uint32 scr[2]) /* Send ACMD51 SD_APP_SEND_SCR with argument as 0 to start data receipt */ - (void)SDIO_WAITENABLE(priv->dev, SDIOWAIT_TRANSFERDONE); + (void)SDIO_WAITENABLE(priv->dev, SDIOWAIT_TRANSFERDONE|SDIOWAIT_TIMEOUT); mmcsd_sendcmdpoll(priv, SD_ACMD51, 0); ret = mmcsd_recvR1(priv, SD_ACMD51); if (ret != OK) @@ -460,7 +462,7 @@ static int mmcsd_getSCR(FAR struct mmcsd_state_s *priv, uint32 scr[2]) /* Wait for data to be transferred */ - ret = SDIO_EVENTWAIT(priv->dev, MMCSD_SCR_DATADELAY); + ret = mmcsd_eventwait(priv, SDIOWAIT_TIMEOUT, MMCSD_SCR_DATADELAY); if (ret != OK) { fdbg("ERROR: EVENTWAIT for READ DATA failed: %d\n", ret); @@ -905,37 +907,100 @@ static int mmcsd_getR1(FAR struct mmcsd_state_s *priv, FAR uint32 *r1) } /**************************************************************************** - * Name: mmcsd_verifystandby + * Name: mmcsd_verifystate * * Description: * Verify that the card is in STANDBY state * ****************************************************************************/ -static int mmcsd_verifystandby(FAR struct mmcsd_state_s *priv) +static int mmcsd_verifystate(FAR struct mmcsd_state_s *priv, uint32 state) { -#warning "Not implemented" - return -ENOSYS; + uint32 r1; + int ret; + + /* Get the current R1 status from the card */ + + ret = mmcsd_getR1(priv, &r1); + if (ret != OK) + { + fdbg("ERROR: mmcsd_getR1 failed: %d\n", ret); + return ret; + } + + /* Now check if the card is in the expected state. */ + + if (IS_STATE(r1, state)) + { + /* Yes.. return Success */ + + priv->wrbusy = FALSE; + return OK; + } + return -EINVAL; } /**************************************************************************** - * Name: mmcsd_verifyidle - * - * Description: - * Verify that the card is in IDLE state - * + * Transfer Helpers ****************************************************************************/ -static int mmcsd_verifyidle(FAR struct mmcsd_state_s *priv) +/**************************************************************************** + * Name: mmcsd_wrprotected + * + * Description: + * Return true if the the card is unlocked an not write protected. The + * + * + ****************************************************************************/ + +static boolean mmcsd_wrprotected(FAR struct mmcsd_state_s *priv) { -#warning "Not implemented" - return -ENOSYS; + /* Check if the card is locked (priv->locked) or write protected either (1) + * via software as reported via the CSD and retained in priv->wrprotect or + * (2) via the mechanical write protect on the card (which we get from the + * SDIO driver via SDIO_WRPROTECTED) + */ + + return (priv->wrprotect || priv->locked || SDIO_WRPROTECTED(priv->dev)); } -/**************************************************************************** - * Transfer Helpers +/**************************************************************************** + * Name: mmcsd_eventwait + * + * Description: + * Wait for the specified events to occur. Check for wakeup on error events. + * ****************************************************************************/ +static int mmcsd_eventwait(FAR struct mmcsd_state_s *priv, + sdio_eventset_t failevents, uint32 timeout) +{ + sdio_eventset_t wkupevent; + + /* Wait for the set of events enabled by SDIO_EVENTENABLE. */ + + wkupevent = SDIO_EVENTWAIT(priv->dev, timeout); + + /* SDIO_EVENTWAIT returns the event set containing the event(s) that ended + * the wait. It should always be non-zero, but may contain failure as + * well as success events. Check if it contains any failure events. + */ + + if ((wkupevent & failevents) != 0) + { + /* Yes.. the failure event is probably SDIOWAIT_TIMEOUT */ + + fdbg("ERROR: Awakened with %02\n", wkupevent); + return wkupevent & SDIOWAIT_TIMEOUT ? -ETIMEDOUT : -EIO; + } + + /* Since there are no failure events, we must have been awaked by one + * (or more) success events. + */ + + return OK; +} + /**************************************************************************** * Name: mmcsd_transferready * @@ -989,7 +1054,7 @@ static int mmcsd_transferready(FAR struct mmcsd_state_s *priv) ret = mmcsd_getR1(priv, &r1); if (ret != OK) { - fdbg("ERROR: mmcsd_recvR1 for CMD12 failed: %d\n", ret); + fdbg("ERROR: mmcsd_getR1 failed: %d\n", ret); return ret; } @@ -1038,7 +1103,7 @@ static int mmcsd_transferready(FAR struct mmcsd_state_s *priv) * ****************************************************************************/ -static int stm32_stoptransmission(FAR struct mmcsd_state_s *priv) +static int mmcsd_stoptransmission(FAR struct mmcsd_state_s *priv) { int ret; @@ -1153,7 +1218,7 @@ static ssize_t mmcsd_readsingle(FAR struct mmcsd_state_s *priv, /* Configure SDIO controller hardware for the read transfer */ - SDIO_WAITENABLE(priv->dev, SDIOWAIT_TRANSFERDONE); + SDIO_WAITENABLE(priv->dev, SDIOWAIT_TRANSFERDONE|SDIOWAIT_TIMEOUT); #ifdef CONFIG_SDIO_DMA if (priv->dma) { @@ -1181,7 +1246,7 @@ static ssize_t mmcsd_readsingle(FAR struct mmcsd_state_s *priv, /* Then wait for the data transfer to complete */ - ret = SDIO_EVENTWAIT(priv->dev, MMCSD_BLOCK_DATADELAY); + ret = mmcsd_eventwait(priv, SDIOWAIT_TIMEOUT, MMCSD_BLOCK_DATADELAY); if (ret != OK) { fdbg("ERROR: CMD17 transfer failed: %d\n", ret); @@ -1256,7 +1321,7 @@ static ssize_t mmcsd_readmultiple(FAR struct mmcsd_state_s *priv, /* Configure SDIO controller hardware for the read transfer */ - SDIO_WAITENABLE(priv->dev, SDIOWAIT_TRANSFERDONE); + SDIO_WAITENABLE(priv->dev, SDIOWAIT_TRANSFERDONE|SDIOWAIT_TIMEOUT); #ifdef CONFIG_SDIO_DMA if (priv->dma) { @@ -1282,7 +1347,7 @@ static ssize_t mmcsd_readmultiple(FAR struct mmcsd_state_s *priv, /* Wait for the transfer to complete */ - ret = SDIO_EVENTWAIT(priv->dev, nblocks * MMCSD_BLOCK_DATADELAY); + ret = mmcsd_eventwait(priv, SDIOWAIT_TIMEOUT, nblocks * MMCSD_BLOCK_DATADELAY); if (ret != OK) { fdbg("ERROR: CMD18 transfer failed: %d\n", ret); @@ -1346,9 +1411,11 @@ static ssize_t mmcsd_writesingle(FAR struct mmcsd_state_s *priv, fvdbg("startblock=%d\n", startblock); DEBUGASSERT(priv != NULL && buffer != NULL); - /* Check if the card is locked or write protected */ + /* Check if the card is locked or write protected (either via software or + * via the mechanical write protect on the card) + */ - if (priv->locked || priv->wrprotect) + if (mmcsd_wrprotected(priv)) { fdbg("ERROR: Card is locked or write protected\n"); return -EPERM; @@ -1403,7 +1470,7 @@ static ssize_t mmcsd_writesingle(FAR struct mmcsd_state_s *priv, /* Configure SDIO controller hardware for the write transfer */ - SDIO_WAITENABLE(priv->dev, SDIOWAIT_TRANSFERDONE); + SDIO_WAITENABLE(priv->dev, SDIOWAIT_TRANSFERDONE|SDIOWAIT_TIMEOUT); #ifdef CONFIG_SDIO_DMA if (priv->dma) { @@ -1417,7 +1484,7 @@ static ssize_t mmcsd_writesingle(FAR struct mmcsd_state_s *priv, /* Wait for the transfer to complete */ - ret = SDIO_EVENTWAIT(priv->dev, MMCSD_BLOCK_DATADELAY); + ret = mmcsd_eventwait(priv, SDIOWAIT_TIMEOUT, MMCSD_BLOCK_DATADELAY); if (ret != OK) { fdbg("ERROR: CMD24 transfer failed: %d\n", ret); @@ -1450,9 +1517,11 @@ static ssize_t mmcsd_writemultiple(FAR struct mmcsd_state_s *priv, fvdbg("startblockr=%d nblocks=%d\n", startblock, nblocks); DEBUGASSERT(priv != NULL && buffer != NULL && nblocks > 1); - /* Check if the card is locked or write protected */ + /* Check if the card is locked or write protected (either via software or + * via the mechanical write protect on the card) + */ - if (priv->locked || priv->wrprotect) + if (mmcsd_wrprotected(priv)) { fdbg("ERROR: Card is locked or write protected\n"); return -EPERM; @@ -1539,7 +1608,7 @@ static ssize_t mmcsd_writemultiple(FAR struct mmcsd_state_s *priv, /* Configure SDIO controller hardware for the write transfer */ - SDIO_WAITENABLE(priv->dev, SDIOWAIT_TRANSFERDONE); + SDIO_WAITENABLE(priv->dev, SDIOWAIT_TRANSFERDONE|SDIOWAIT_TIMEOUT); #ifdef CONFIG_SDIO_DMA if (priv->dma) { @@ -1553,7 +1622,7 @@ static ssize_t mmcsd_writemultiple(FAR struct mmcsd_state_s *priv, /* Wait for the transfer to complete */ - ret = SDIO_EVENTWAIT(priv->dev, nblocks * MMCSD_BLOCK_DATADELAY); + ret =mmcsd_eventwait(priv, SDIOWAIT_TIMEOUT, nblocks * MMCSD_BLOCK_DATADELAY); if (ret != OK) { fdbg("ERROR: CMD18 transfer failed: %d\n", ret); @@ -1768,7 +1837,7 @@ static int mmcsd_geometry(FAR struct inode *inode, struct geometry *geometry) geometry->geo_available = TRUE; geometry->geo_mediachanged = priv->mediachanged; #ifdef CONFIG_FS_WRITABLE - geometry->geo_writeenabled = !priv->wrprotect && !priv->locked; + geometry->geo_writeenabled = !mmcsd_wrprotected(priv); #else geometry->geo_writeenabled = FALSE; #endif @@ -2047,7 +2116,7 @@ static int mmcsd_mmcinitialize(FAR struct mmcsd_state_s *priv) * Verify that we are in standby state/data-transfer mode */ - ret = mmcsd_verifystandby(priv); + ret = mmcsd_verifystate(priv, MMCSD_R1_STATE_STBY); if (ret != OK) { fdbg("ERROR: Failed to enter standby state\n"); @@ -2149,7 +2218,7 @@ static int mmcsd_sdinitialize(FAR struct mmcsd_state_s *priv) * Verify that we are in standby state/data-transfer mode */ - ret = mmcsd_verifystandby(priv); + ret = mmcsd_verifystate(priv, MMCSD_R1_STATE_STBY); if (ret != OK) { fdbg("ERROR: Failed to enter standby state\n"); @@ -2452,7 +2521,7 @@ static int mmcsd_cardidentify(FAR struct mmcsd_state_s *priv) /* Verify that we are in IDLE state */ - ret = mmcsd_verifyidle(priv); + ret = mmcsd_verifystate(priv, MMCSD_R1_STATE_IDLE); if (ret != OK) { fdbg("ERROR: Failed to enter IDLE state\n"); @@ -2726,26 +2795,23 @@ static void mmcsd_hwuninitialize(FAR struct mmcsd_state_s *priv) * Input Parameters: * minor - The MMC/SD minor device number. The MMC/SD device will be * registered as /dev/mmcsdN where N is the minor number - * slotno - The slot number to use. This is only meaningful for architectures - * that support multiple MMC/SD slots. This value must be in the range - * {0, ..., CONFIG_MMCSD_NSLOTS}. * dev - And instance of an MMC/SD interface. The MMC/SD hardware should * be initialized and ready to use. * ****************************************************************************/ -int mmcsd_slotinitialize(int minor, int slotno, FAR struct sdio_dev_s *dev) +int mmcsd_slotinitialize(int minor, FAR struct sdio_dev_s *dev) { FAR struct mmcsd_state_s *priv; char devname[16]; int ret = -ENOMEM; - fvdbg("minor: %d slotno: %d\n", minor, slotno); + fvdbg("minor: %d\n", minor); /* Sanity check */ #ifdef CONFIG_DEBUG - if ((unsigned)slotno >= CONFIG_MMCSD_NSLOTS || minor < 0 || minor > 255 || !dev) + if (minor < 0 || minor > 255 || !dev) { return -EINVAL; } @@ -2780,12 +2846,11 @@ int mmcsd_slotinitialize(int minor, int slotno, FAR struct sdio_dev_s *dev) if (ret == -ENODEV) { - fdbg("MMC/SD slot %d is empty\n", slotno); + fdbg("MMC/SD slot is empty\n"); } else { - fdbg("ERROR: Failed to initialize MMC/SD slot %d: %d\n", - slotno, ret); + fdbg("ERROR: Failed to initialize MMC/SD slot: %d\n", ret); goto errout_with_alloc; } } diff --git a/nuttx/include/nuttx/mmcsd.h b/nuttx/include/nuttx/mmcsd.h index 94b4aede1..f9d4a47b4 100644 --- a/nuttx/include/nuttx/mmcsd.h +++ b/nuttx/include/nuttx/mmcsd.h @@ -72,16 +72,13 @@ extern "C" { * Input Parameters: * minor - The MMC/SD minor device number. The MMC/SD device will be * registered as /dev/mmcsdN where N is the minor number - * slotno - The slot number to use. This is only meaningful for architectures - * that support multiple MMC/SD slots. This value must be in the range - * {0, ..., CONFIG_MMCSD_NSLOTS}. * dev - And instance of an MMC/SD interface. The MMC/SD hardware should * be initialized and ready to use. * ****************************************************************************/ struct sdio_dev_s; /* See nuttx/sdio.h */ -EXTERN int mmcsd_slotinitialize(int minor, int slotno, FAR struct sdio_dev_s *dev); +EXTERN int mmcsd_slotinitialize(int minor, FAR struct sdio_dev_s *dev); /**************************************************************************** * Name: mmcsd_spislotinitialize diff --git a/nuttx/include/nuttx/sdio.h b/nuttx/include/nuttx/sdio.h index 497164c39..23dc3d458 100755 --- a/nuttx/include/nuttx/sdio.h +++ b/nuttx/include/nuttx/sdio.h @@ -55,8 +55,9 @@ #define SDIOWAIT_CMDDONE (1 << 0) /* Bit 0: Command complete */ #define SDIOWAIT_RESPONSEDONE (1 << 1) /* Bit 1: Response to command available */ #define SDIOWAIT_TRANSFERDONE (1 << 2) /* Bit 2: Data transfer/DMA done */ +#define SDIOWAIT_TIMEOUT (1 << 3) /* Bit 3: Timeout */ -#define SDIOWAIT_ALLEVENTS 0x07 +#define SDIOWAIT_ALLEVENTS 0x0f /* Media events are used for enable/disable registered event callbacks */ @@ -525,35 +526,18 @@ * * Input Parameters: * dev - An instance of the SDIO device interface - * timeout - Maximum time in milliseconds to wait. Zero means no timeout. + * timeout - Maximum time in milliseconds to wait. Zero means immediate + * timeout with no wait. The timeout value is ignored if + * SDIOWAIT_TIMEOUT is not included in the waited-for eventset. * * Returned Value: - * Event set containing the event(s) that ended the wait. If no events the - * returned event set is zero, then the wait was terminated by the timeout. - * All events are cleared disabled after the wait concludes. + * Event set containing the event(s) that ended the wait. Should always + * be non-zero. All events are disabled after the wait concludes. * ****************************************************************************/ #define SDIO_EVENTWAIT(dev,timeout) ((dev)->eventwait(dev,timeout)) -/**************************************************************************** - * Name: SDIO_EVENTS - * - * Description: - * Return the current event set. This supports polling for SDIO (vs. - * waiting). Only enabled events need be reported. - * - * Input Parameters: - * dev - An instance of the SDIO device interface - * - * Returned Value: - * Event set containing the current events (All pending events are cleared - * after reading). - * - ****************************************************************************/ - -#define SDIO_EVENTS(dev) ((dev)->events(dev)) - /**************************************************************************** * Name: SDIO_CALLBACKENABLE * @@ -736,13 +720,14 @@ struct sdio_dev_s int (*recvR6)(FAR struct sdio_dev_s *dev, uint32 cmd, uint32 *R6); int (*recvR7)(FAR struct sdio_dev_s *dev, uint32 cmd, uint32 *R7); - /* EVENT handler */ + /* Event/Callback support */ void (*waitenable)(FAR struct sdio_dev_s *dev, sdio_eventset_t eventset); - ubyte (*eventwait)(FAR struct sdio_dev_s *dev, uint32 timeout); - ubyte (*events)(FAR struct sdio_dev_s *dev); - void (*callbackenable)(FAR struct sdio_dev_s *dev, sdio_eventset_t eventset); - int (*registercallback)(FAR struct sdio_dev_s *dev, sdio_mediachange_t callback, void *arg); + sdio_eventset_t (*eventwait)(FAR struct sdio_dev_s *dev, uint32 timeout); + void (*callbackenable)(FAR struct sdio_dev_s *dev, + sdio_eventset_t eventset); + int (*registercallback)(FAR struct sdio_dev_s *dev, + sdio_mediachange_t callback, void *arg); /* DMA */ -- cgit v1.2.3