summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/Documentation/NuttxPortingGuide.html21
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_sdio.c2392
-rw-r--r--nuttx/configs/README.txt8
-rwxr-xr-xnuttx/configs/stm3210e-eval/README.txt6
-rwxr-xr-xnuttx/configs/stm3210e-eval/RIDE/defconfig49
-rwxr-xr-xnuttx/configs/stm3210e-eval/nsh/defconfig53
-rwxr-xr-xnuttx/configs/stm3210e-eval/ostest/defconfig49
-rwxr-xr-xnuttx/configs/stm3210e-eval/usbserial/defconfig49
-rw-r--r--nuttx/drivers/mmcsd/mmcsd_sdio.c268
-rwxr-xr-xnuttx/include/nuttx/sdio.h17
-rwxr-xr-xnuttx/include/nuttx/wqueue.h3
-rwxr-xr-xnuttx/sched/work_internal.h2
12 files changed, 1578 insertions, 1339 deletions
diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html
index c3093d8b7..1ce105c8f 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: November 5, 2009</p>
+ <p>Last Updated: November 17, 2009</p>
</td>
</tr>
</table>
@@ -2288,6 +2288,25 @@ extern void up_ledoff(int led);
</li>
</ul>
+<h2>SDIO-based MMC/SD driver</h2>
+<ul>
+ <li>
+ <code>CONFIG_FS_READAHEAD</code>: Enable read-ahead buffering
+ </li>
+ <li>
+ <code>CONFIG_FS_WRITEBUFFER</code>: Enable write buffering
+ </li>
+ <li>
+ <code>CONFIG_SDIO_DMA</code>: SDIO driver supports DMA
+ </li>
+ <li>
+ <code>CONFIG_MMCSD_MMCSUPPORT</code>: Enable support for MMC cards
+ </li>
+ <li>
+ <code>CONFIG_MMCSD_HAVECARDDETECT</code>: SDIO driver card detection is 100% accurate
+ </li>
+</ul>
+
<h2>Network Support</h2>
<h3>TCP/IP and UDP support via uIP</h2>
<ul>
diff --git a/nuttx/arch/arm/src/stm32/stm32_sdio.c b/nuttx/arch/arm/src/stm32/stm32_sdio.c
index f76b55988..01a458834 100644
--- a/nuttx/arch/arm/src/stm32/stm32_sdio.c
+++ b/nuttx/arch/arm/src/stm32/stm32_sdio.c
@@ -39,22 +39,23 @@
#include <nuttx/config.h>
#include <sys/types.h>
-
-#include <semaphore.h>
+
+#include <semaphore.h>
#include <assert.h>
-#include <debug.h>
+#include <debug.h>
#include <wdog.h>
#include <errno.h>
#include <nuttx/clock.h>
-#include <nuttx/arch.h>
-#include <nuttx/sdio.h>
-#include <nuttx/mmcsd.h>
+#include <nuttx/arch.h>
+#include <nuttx/sdio.h>
+#include <nuttx/wqueue.h>
+#include <nuttx/mmcsd.h>
#include <arch/irq.h>
#include "chip.h"
#include "up_arch.h"
-#include "stm32_internal.h"
+#include "stm32_internal.h"
#include "stm32_dma.h"
#include "stm32_sdio.h"
@@ -69,14 +70,18 @@
#if defined(CONFIG_SDIO_DMA) && !defined(CONFIG_STM32_DMA2)
# warning "CONFIG_SDIO_DMA support requires CONFIG_STM32_DMA2"
# undef CONFIG_SDIO_DMA
-#endif
-
-#ifndef CONFIG_SDIO_PRI
-# define CONFIG_SDIO_PRI DMA_CCR_PRIMED
#endif
-
-#ifndef CONFIG_SDIO_DMAPRIO
-# define CONFIG_SDIO_DMAPRIO DMA_CCR_PRIMED
+
+#ifndef CONFIG_SCHED_WORKQUEUE
+# error "Callback support requires CONFIG_SCHED_WORKQUEUE"
+#endif
+
+#ifndef CONFIG_SDIO_PRI
+# define CONFIG_SDIO_PRI DMA_CCR_PRIMED
+#endif
+
+#ifndef CONFIG_SDIO_DMAPRIO
+# define CONFIG_SDIO_DMAPRIO DMA_CCR_PRIMED
#endif
/* Friendly CLKCR bit re-definitions ****************************************/
@@ -87,80 +92,80 @@
/* 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|\
+#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|\
+#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_SDXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT)
-#define SDIO_CLCKR_SDXFR (SDIO_SDXFR_CLKDIV|SDIO_CLKCR_RISINGEDGE|\
+#define SDIO_CLCKR_SDXFR (SDIO_SDXFR_CLKDIV|SDIO_CLKCR_RISINGEDGE|\
SDIO_CLKCR_WIDBUS_D1)
-#define SDIO_CLCKR_SDWIDEXFR (SDIO_SDXFR_CLKDIV|SDIO_CLKCR_RISINGEDGE|\
- SDIO_CLKCR_WIDBUS_D4)
-
-/* Timing */
-
-#define SDIO_CMDTIMEOUT (100000)
-#define SDIO_LONGTIMEOUT (0x7fffffff)
-
-/* Big DTIMER setting */
-
-#define SDIO_DTIMER_DATATIMEOUT (0x000fffff)
-
-/* DMA CCR register settings */
-
-#define SDIO_RXDMA16_CONFIG (CONFIG_SDIO_DMAPRIO|DMA_CCR_MSIZE_16BITS|\
- DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC)
-#define SDIO_TXDMA16_CONFIG (CONFIG_SDIO_DMAPRIO|DMA_CCR_MSIZE_16BITS|\
- DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC|DMA_CCR_DIR)
-
-/* FIFO sizes */
-
+#define SDIO_CLCKR_SDWIDEXFR (SDIO_SDXFR_CLKDIV|SDIO_CLKCR_RISINGEDGE|\
+ SDIO_CLKCR_WIDBUS_D4)
+
+/* Timing */
+
+#define SDIO_CMDTIMEOUT (100000)
+#define SDIO_LONGTIMEOUT (0x7fffffff)
+
+/* Big DTIMER setting */
+
+#define SDIO_DTIMER_DATATIMEOUT (0x000fffff)
+
+/* DMA CCR register settings */
+
+#define SDIO_RXDMA16_CONFIG (CONFIG_SDIO_DMAPRIO|DMA_CCR_MSIZE_16BITS|\
+ DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC)
+#define SDIO_TXDMA16_CONFIG (CONFIG_SDIO_DMAPRIO|DMA_CCR_MSIZE_16BITS|\
+ DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC|DMA_CCR_DIR)
+
+/* FIFO sizes */
+
#define SDIO_HALFFIFO_WORDS (8)
-#define SDIO_HALFFIFO_BYTES (8*4)
-
-/* Data transfer interrupt mask bits */
-
-#define SDIO_RECV_MASK (SDIO_MASK_DCRCFAILIE|SDIO_MASK_DTIMEOUTIE|\
- SDIO_MASK_DATAENDIE|SDIO_MASK_RXOVERRIE|\
- SDIO_MASK_RXFIFOHFIE|SDIO_MASK_STBITERRIE)
-#define SDIO_SEND_MASK (SDIO_MASK_DCRCFAILIE|SDIO_MASK_DTIMEOUTIE|\
- SDIO_MASK_DATAENDIE|SDIO_MASK_TXUNDERRIE|\
- SDIO_MASK_TXFIFOHEIE|SDIO_MASK_STBITERRIE)
-#define SDIO_DMARECV_MASK (SDIO_MASK_DCRCFAILIE|SDIO_MASK_DTIMEOUTIE|\
- SDIO_MASK_DATAENDIE|SDIO_MASK_RXOVERRIE|\
- SDIO_MASK_STBITERRIE)
-#define SDIO_DMASEND_MASK (SDIO_MASK_DCRCFAILIE|SDIO_MASK_DTIMEOUTIE|\
- SDIO_MASK_DATAENDIE|SDIO_MASK_TXUNDERRIE|\
- SDIO_MASK_STBITERRIE)
-
-/* Event waiting interrupt mask bits */
-
-#define SDIO_CMDDONE_STA (SDIO_STA_CMDSENT)
-#define SDIO_CRCRESP_STA (SDIO_STA_CTIMEOUT|SDIO_STA_CCRCFAIL|SDIO_STA_CMDREND)
-#define SDIO_RESPDONE_STA (SDIO_STA_CTIMEOUT|SDIO_STA_CMDREND)
-#define SDIO_XFRDONE_STA (0)
-
-#define SDIO_CMDDONE_MASK (SDIO_MASK_CMDSENTIE)
-#define SDIO_CRCRESP_MASK (SDIO_MASK_CCRCFAILIE|SDIO_MASK_CTIMEOUTIE|\
- SDIO_MASK_CMDRENDIE)
-#define SDIO_RESPDONE_MASK (SDIO_MASK_CTIMEOUTIE|SDIO_MASK_CMDRENDIE)
-#define SDIO_XFRDONE_MASK (0)
-
-#define SDIO_CMDDONE_ICR (SDIO_ICR_CMDSENTC)
-#define SDIO_CRCRESP_ICR (SDIO_ICR_CTIMEOUTC|SDIO_ICR_CCRCFAILC|SDIO_ICR_CMDRENDC)
-#define SDIO_RESPDONE_ICR (SDIO_ICR_CTIMEOUTC|SDIO_ICR_CMDRENDC)
-#define SDIO_XFRDONE_ICR (0)
-
-#define SDIO_WAITALL_ICR (SDIO_ICR_CMDSENTC|SDIO_ICR_CTIMEOUTC|\
- SDIO_ICR_CCRCFAILC|SDIO_ICR_CMDRENDC)
-
+#define SDIO_HALFFIFO_BYTES (8*4)
+
+/* Data transfer interrupt mask bits */
+
+#define SDIO_RECV_MASK (SDIO_MASK_DCRCFAILIE|SDIO_MASK_DTIMEOUTIE|\
+ SDIO_MASK_DATAENDIE|SDIO_MASK_RXOVERRIE|\
+ SDIO_MASK_RXFIFOHFIE|SDIO_MASK_STBITERRIE)
+#define SDIO_SEND_MASK (SDIO_MASK_DCRCFAILIE|SDIO_MASK_DTIMEOUTIE|\
+ SDIO_MASK_DATAENDIE|SDIO_MASK_TXUNDERRIE|\
+ SDIO_MASK_TXFIFOHEIE|SDIO_MASK_STBITERRIE)
+#define SDIO_DMARECV_MASK (SDIO_MASK_DCRCFAILIE|SDIO_MASK_DTIMEOUTIE|\
+ SDIO_MASK_DATAENDIE|SDIO_MASK_RXOVERRIE|\
+ SDIO_MASK_STBITERRIE)
+#define SDIO_DMASEND_MASK (SDIO_MASK_DCRCFAILIE|SDIO_MASK_DTIMEOUTIE|\
+ SDIO_MASK_DATAENDIE|SDIO_MASK_TXUNDERRIE|\
+ SDIO_MASK_STBITERRIE)
+
+/* Event waiting interrupt mask bits */
+
+#define SDIO_CMDDONE_STA (SDIO_STA_CMDSENT)
+#define SDIO_CRCRESP_STA (SDIO_STA_CTIMEOUT|SDIO_STA_CCRCFAIL|SDIO_STA_CMDREND)
+#define SDIO_RESPDONE_STA (SDIO_STA_CTIMEOUT|SDIO_STA_CMDREND)
+#define SDIO_XFRDONE_STA (0)
+
+#define SDIO_CMDDONE_MASK (SDIO_MASK_CMDSENTIE)
+#define SDIO_CRCRESP_MASK (SDIO_MASK_CCRCFAILIE|SDIO_MASK_CTIMEOUTIE|\
+ SDIO_MASK_CMDRENDIE)
+#define SDIO_RESPDONE_MASK (SDIO_MASK_CTIMEOUTIE|SDIO_MASK_CMDRENDIE)
+#define SDIO_XFRDONE_MASK (0)
+
+#define SDIO_CMDDONE_ICR (SDIO_ICR_CMDSENTC)
+#define SDIO_CRCRESP_ICR (SDIO_ICR_CTIMEOUTC|SDIO_ICR_CCRCFAILC|SDIO_ICR_CMDRENDC)
+#define SDIO_RESPDONE_ICR (SDIO_ICR_CTIMEOUTC|SDIO_ICR_CMDRENDC)
+#define SDIO_XFRDONE_ICR (0)
+
+#define SDIO_WAITALL_ICR (SDIO_ICR_CMDSENTC|SDIO_ICR_CTIMEOUTC|\
+ SDIO_ICR_CCRCFAILC|SDIO_ICR_CMDRENDC)
+
/****************************************************************************
* Private Types
****************************************************************************/
@@ -172,34 +177,35 @@ struct stm32_dev_s
struct sdio_dev_s dev; /* Standard, base SDIO interface */
/* STM32-specific extensions */
- /* Event support */
-
+ /* 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 */
-
- /* Interrupt mode data transfer support */
-
- uint32 *buffer; /* Address of current R/W buffer */
- size_t remaining; /* Number of bytes remaining in the transfer */
- int result; /* Result of the transfer */
- uint32 xfrmask; /* Interrupt enables for data transfer */
-
- /* DMA data transfer support */
-
- boolean widebus; /* Required for DMA support */
-#ifdef CONFIG_SDIO_DMA
- boolean dmamode; /* TRUE: DMA mode transfer */
- DMA_HANDLE dma; /* Handle for DMA channel */
+ 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 */
+ worker_t callback; /* Registered callback function */
+ void *cbarg; /* Registered callback argument */
+ struct work_s cbwork; /* Callback work queue structure */
+
+ /* Interrupt mode data transfer support */
+
+ uint32 *buffer; /* Address of current R/W buffer */
+ size_t remaining; /* Number of bytes remaining in the transfer */
+ int result; /* Result of the transfer */
+ uint32 xfrmask; /* Interrupt enables for data transfer */
+
+ /* DMA data transfer support */
+
+ boolean widebus; /* Required for DMA support */
+#ifdef CONFIG_SDIO_DMA
+ boolean dmamode; /* TRUE: DMA mode transfer */
+ DMA_HANDLE dma; /* Handle for DMA channel */
#endif
};
@@ -209,35 +215,35 @@ struct stm32_dev_s
/* Low-level helpers ********************************************************/
-static void stm32_takesem(struct stm32_dev_s *priv);
-#define stm32_givesem(priv) (sem_post(&priv->waitsem))
+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,
- sdio_eventset_t waitevents, sdio_eventset_t wkupevents);
-static void stm32_configxfrints(struct stm32_dev_s *priv, uint32 xfrmask);
+static void stm32_configwaitints(struct stm32_dev_s *priv, uint32 waitmask,
+ 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);
-
-/* DMA Helpers **************************************************************/
+
+/* DMA Helpers **************************************************************/
#ifdef CONFIG_SDIO_DMA
-static void stm32_dmacallback(DMA_HANDLE handle, ubyte isr, void *arg);
-#endif
-
+static void stm32_dmacallback(DMA_HANDLE handle, ubyte isr, void *arg);
+#endif
+
/* Data Transfer Helpers ****************************************************/
-
+
static ubyte stm32_log2(uint16 value);
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_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 *******************************************************/
+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_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 *******************************************************/
-static int stm32_interrupt(int irq, void *context);
+static int stm32_interrupt(int irq, void *context);
/* SDIO interface methods ***************************************************/
@@ -252,33 +258,33 @@ static int stm32_attach(FAR struct sdio_dev_s *dev);
/* Command/Status/Data Transfer */
-static void stm32_sendcmd(FAR struct sdio_dev_s *dev, uint32 cmd,
- uint32 arg);
-static int stm32_recvsetup(FAR struct sdio_dev_s *dev, FAR ubyte *buffer,
- size_t nbytes);
-static int stm32_sendsetup(FAR struct sdio_dev_s *dev,
+static void stm32_sendcmd(FAR struct sdio_dev_s *dev, uint32 cmd,
+ uint32 arg);
+static int stm32_recvsetup(FAR struct sdio_dev_s *dev, FAR ubyte *buffer,
+ size_t nbytes);
+static int stm32_sendsetup(FAR struct sdio_dev_s *dev,
FAR const ubyte *buffer, uint32 nbytes);
-
+
static int stm32_waitresponse(FAR struct sdio_dev_s *dev, uint32 cmd);
-static int stm32_recvshortcrc(FAR struct sdio_dev_s *dev, uint32 cmd,
+static int stm32_recvshortcrc(FAR struct sdio_dev_s *dev, uint32 cmd,
uint32 *rshort);
-static int stm32_recvlong(FAR struct sdio_dev_s *dev, uint32 cmd,
+static int stm32_recvlong(FAR struct sdio_dev_s *dev, uint32 cmd,
uint32 rlong[4]);
-static int stm32_recvshort(FAR struct sdio_dev_s *dev, uint32 cmd,
+static int stm32_recvshort(FAR struct sdio_dev_s *dev, uint32 cmd,
uint32 *rshort);
-static int stm32_recvnotimpl(FAR struct sdio_dev_s *dev, uint32 cmd,
+static int stm32_recvnotimpl(FAR struct sdio_dev_s *dev, uint32 cmd,
uint32 *rnotimpl);
/* EVENT handler */
-static void stm32_waitenable(FAR struct sdio_dev_s *dev,
+static void stm32_waitenable(FAR struct sdio_dev_s *dev,
sdio_eventset_t eventset);
-static sdio_eventset_t
+static sdio_eventset_t
stm32_eventwait(FAR struct sdio_dev_s *dev, uint32 timeout);
-static void stm32_callbackenable(FAR struct sdio_dev_s *dev,
+static void stm32_callbackenable(FAR struct sdio_dev_s *dev,
sdio_eventset_t eventset);
-static int stm32_registercallback(FAR struct sdio_dev_s *dev,
- sdio_mediachange_t callback, void *arg);
+static int stm32_registercallback(FAR struct sdio_dev_s *dev,
+ worker_t callback, void *arg);
/* DMA */
@@ -291,7 +297,7 @@ static int stm32_dmasendsetup(FAR struct sdio_dev_s *dev,
#endif
/* Initialization/uninitialization/reset ************************************/
-
+
static void stm32_callback(void *arg);
static void stm32_default(void);
@@ -308,7 +314,7 @@ struct stm32_dev_s g_sdiodev =
.widebus = stm32_widebus,
.clock = stm32_clock,
.attach = stm32_attach,
- .sendcmd = stm32_sendcmd,
+ .sendcmd = stm32_sendcmd,
.recvsetup = stm32_recvsetup,
.sendsetup = stm32_sendsetup,
.waitresponse = stm32_waitresponse,
@@ -318,10 +324,10 @@ struct stm32_dev_s g_sdiodev =
.recvR4 = stm32_recvnotimpl,
.recvR5 = stm32_recvnotimpl,
.recvR6 = stm32_recvshortcrc,
- .recvR7 = stm32_recvshort,
+ .recvR7 = stm32_recvshort,
.waitenable = stm32_waitenable,
.eventwait = stm32_eventwait,
- .callbackenable = stm32_callbackenable,
+ .callbackenable = stm32_callbackenable,
.registercallback = stm32_registercallback,
#ifdef CONFIG_SDIO_DMA
.dmasupported = stm32_dmasupported,
@@ -342,7 +348,7 @@ struct stm32_dev_s g_sdiodev =
* Name: stm32_takesem
*
* Description:
- * Take the wait semaphore (handling false alarm wakeups due to the receipt
+ * Take the wait semaphore (handling false alarm wakeups due to the receipt
* of signals).
*
* Input Parameters:
@@ -352,21 +358,21 @@ struct stm32_dev_s g_sdiodev =
* None
*
****************************************************************************/
-
-static void stm32_takesem(struct stm32_dev_s *priv)
-{
- /* Take the semaphore (perhaps waiting) */
-
- while (sem_wait(&priv->waitsem) != 0)
- {
- /* The only case that an error should occr here is if the wait was
- * awakened by a signal.
- */
-
- ASSERT(errno == EINTR);
- }
-}
-
+
+static void stm32_takesem(struct stm32_dev_s *priv)
+{
+ /* Take the semaphore (perhaps waiting) */
+
+ while (sem_wait(&priv->waitsem) != 0)
+ {
+ /* The only case that an error should occr here is if the wait was
+ * awakened by a signal.
+ */
+
+ ASSERT(errno == EINTR);
+ }
+}
+
/****************************************************************************
* Name: stm32_setclkcr
*
@@ -410,35 +416,35 @@ static inline void stm32_setclkcr(uint32 clkcr)
*
* Input Parameters:
* 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
+ * waitmask - The set of bits in the SDIO MASK register to set
+ * waitevents - Waited for events
* wkupevent - Wake-up events
*
* Returned Value:
* None
*
****************************************************************************/
-
-static void stm32_configwaitints(struct stm32_dev_s *priv, uint32 waitmask,
- sdio_eventset_t waitevents,
- sdio_eventset_t wkupevent)
-{
- irqstate_t flags;
- flags = irqsave();
- priv->waitevents = waitevents;
- priv->wkupevent = wkupevent;
- priv->waitmask = waitmask;
- putreg32(priv->xfrmask | priv->waitmask, STM32_SDIO_MASK);
+
+static void stm32_configwaitints(struct stm32_dev_s *priv, uint32 waitmask,
+ sdio_eventset_t waitevents,
+ sdio_eventset_t wkupevent)
+{
+ irqstate_t flags;
+ flags = irqsave();
+ priv->waitevents = waitevents;
+ priv->wkupevent = wkupevent;
+ priv->waitmask = waitmask;
+ putreg32(priv->xfrmask | priv->waitmask, STM32_SDIO_MASK);
irqrestore(flags);
-}
-
+}
+
/****************************************************************************
* Name: stm32_configxfrints
*
* Description:
* Enable SDIO interrupts needed to support the data transfer event
*
- * Input Parameters:
+ * Input Parameters:
* priv - A reference to the SDIO device state structure
* xfrmask - The set of bits in the SDIO MASK register to set
*
@@ -447,15 +453,15 @@ static void stm32_configwaitints(struct stm32_dev_s *priv, uint32 waitmask,
*
****************************************************************************/
-static void stm32_configxfrints(struct stm32_dev_s *priv, uint32 xfrmask)
-{
- irqstate_t flags;
- flags = irqsave();
- priv->xfrmask = xfrmask;
- putreg32(priv->xfrmask | priv->waitmask, STM32_SDIO_MASK);
+static void stm32_configxfrints(struct stm32_dev_s *priv, uint32 xfrmask)
+{
+ irqstate_t flags;
+ flags = irqsave();
+ priv->xfrmask = xfrmask;
+ putreg32(priv->xfrmask | priv->waitmask, STM32_SDIO_MASK);
irqrestore(flags);
-}
-
+}
+
/****************************************************************************
* Name: stm32_setpwrctrl
*
@@ -501,55 +507,55 @@ static inline uint32 stm32_getpwrctrl(void)
{
return getreg32(STM32_SDIO_POWER) & SDIO_POWER_PWRCTRL_MASK;
}
-
+
/****************************************************************************
* DMA Helpers
- ****************************************************************************/
+ ****************************************************************************/
/****************************************************************************
- * Name: stm32_dmacallback
- *
- * Description:
- * Called when SDIO DMA completes
- *
- ****************************************************************************/
+ * Name: stm32_dmacallback
+ *
+ * Description:
+ * Called when SDIO DMA completes
+ *
+ ****************************************************************************/
#ifdef CONFIG_SDIO_DMA
-static void stm32_dmacallback(DMA_HANDLE handle, ubyte isr, void *arg)
-{
- /* FAR struct stm32_spidev_s *priv = (FAR struct stm32_spidev_s *)arg; */
-
- /* We don't really do anything at the completion of DMA. The termination
- * of the transfer is driven by the SDIO interrupts.
- */
-}
-#endif
-
+static void stm32_dmacallback(DMA_HANDLE handle, ubyte isr, void *arg)
+{
+ /* FAR struct stm32_spidev_s *priv = (FAR struct stm32_spidev_s *)arg; */
+
+ /* We don't really do anything at the completion of DMA. The termination
+ * of the transfer is driven by the SDIO interrupts.
+ */
+}
+#endif
+
/****************************************************************************
* Data Transfer Helpers
****************************************************************************/
-
+
/****************************************************************************
- * Name: stm32_log2
- *
- * Description:
- * Take (approximate) log base 2 of the provided number (Only works if the
- * provided number is a power of 2).
- *
- ****************************************************************************/
+ * Name: stm32_log2
+ *
+ * Description:
+ * Take (approximate) log base 2 of the provided number (Only works if the
+ * provided number is a power of 2).
+ *
+ ****************************************************************************/
static ubyte stm32_log2(uint16 value)
{
- ubyte log2 = 0;
-
- /* 0000 0000 0000 0001 -> return 0,
+ ubyte log2 = 0;
+
+ /* 0000 0000 0000 0001 -> return 0,
* 0000 0000 0000 001x -> return 1,
* 0000 0000 0000 01xx -> return 2,
- * 0000 0000 0000 1xxx -> return 3,
+ * 0000 0000 0000 1xxx -> return 3,
* ...
- * 1xxx xxxx xxxx xxxx -> return 15,
+ * 1xxx xxxx xxxx xxxx -> return 15,
*/
-
+
DEBUGASSERT(value > 0);
while (value != 1)
{
@@ -558,58 +564,58 @@ static ubyte stm32_log2(uint16 value)
}
return log2;
}
-
+
/****************************************************************************
- * Name: stm32_dataconfig
- *
- * Description:
- * Configure the SDIO data path for the next data transfer
- *
+ * Name: stm32_dataconfig
+ *
+ * Description:
+ * Configure the SDIO data path for the next data transfer
+ *
****************************************************************************/
-
+
static void stm32_dataconfig(uint32 timeout, uint32 dlen, uint32 dctrl)
{
uint32 regval = 0;
-
- /* Enable data path */
-
+
+ /* Enable data path */
+
putreg32(timeout, STM32_SDIO_DTIMER); /* Set DTIMER */
- putreg32(dlen, STM32_SDIO_DLEN); /* Set DLEN */
-
- /* Configure DCTRL DTDIR, DTMODE, and DBLOCKSIZE fields and set the DTEN
- * field
- */
-
- regval = getreg32(STM32_SDIO_DCTRL);
- regval &= ~(SDIO_DCTRL_DTDIR|SDIO_DCTRL_DTMODE|SDIO_DCTRL_DBLOCKSIZE_MASK);
- dctrl &= (SDIO_DCTRL_DTDIR|SDIO_DCTRL_DTMODE|SDIO_DCTRL_DBLOCKSIZE_MASK);
- regval |= (dctrl|SDIO_DCTRL_DTEN);
+ putreg32(dlen, STM32_SDIO_DLEN); /* Set DLEN */
+
+ /* Configure DCTRL DTDIR, DTMODE, and DBLOCKSIZE fields and set the DTEN
+ * field
+ */
+
+ regval = getreg32(STM32_SDIO_DCTRL);
+ regval &= ~(SDIO_DCTRL_DTDIR|SDIO_DCTRL_DTMODE|SDIO_DCTRL_DBLOCKSIZE_MASK);
+ dctrl &= (SDIO_DCTRL_DTDIR|SDIO_DCTRL_DTMODE|SDIO_DCTRL_DBLOCKSIZE_MASK);
+ regval |= (dctrl|SDIO_DCTRL_DTEN);
putreg32(regval, STM32_SDIO_DCTRL);
-}
-
+}
+
/****************************************************************************
- * Name: stm32_datadisable
- *
- * Description:
- * Disable the the SDIO data path setup by stm32_dataconfig() and
- * disable DMA.
- *
+ * Name: stm32_datadisable
+ *
+ * Description:
+ * Disable the the SDIO data path setup by stm32_dataconfig() and
+ * disable DMA.
+ *
****************************************************************************/
-
+
static void stm32_datadisable(void)
-{
+{
uint32 regval;
-
- /* Disable the data path */
-
+
+ /* Disable the data path */
+
putreg32(SDIO_DTIMER_DATATIMEOUT, STM32_SDIO_DTIMER); /* Reset DTIMER */
- putreg32(0, STM32_SDIO_DLEN); /* Reset DLEN */
-
- /* Reset DCTRL DTEN, DTDIR, DTMODE, DMAEN, and DBLOCKSIZE fields */
-
- regval = getreg32(STM32_SDIO_DCTRL);
- regval &= ~(SDIO_DCTRL_DTEN|SDIO_DCTRL_DTDIR|SDIO_DCTRL_DTMODE|
- SDIO_DCTRL_DMAEN|SDIO_DCTRL_DBLOCKSIZE_MASK);
+ putreg32(0, STM32_SDIO_DLEN); /* Reset DLEN */
+
+ /* Reset DCTRL DTEN, DTDIR, DTMODE, DMAEN, and DBLOCKSIZE fields */
+
+ regval = getreg32(STM32_SDIO_DCTRL);
+ regval &= ~(SDIO_DCTRL_DTEN|SDIO_DCTRL_DTDIR|SDIO_DCTRL_DTMODE|
+ SDIO_DCTRL_DMAEN|SDIO_DCTRL_DBLOCKSIZE_MASK);
putreg32(regval, STM32_SDIO_DCTRL);
}
@@ -626,55 +632,55 @@ static void stm32_datadisable(void)
* None
*
****************************************************************************/
-
-static void stm32_sendfifo(struct stm32_dev_s *priv)
-{
- union
- {
- uint32 w;
- ubyte b[2];
- } data;
-
- /* Loop while there is more data to be sent and the RX FIFO is not full */
-
- while (priv->remaining > 0 &&
- (getreg32(STM32_SDIO_STA) & SDIO_STA_TXFIFOF) == 0)
- {
- /* Is there a full word remaining in the user buffer? */
-
- if (priv->remaining >= sizeof(uint32))
- {
- /* Yes, transfer the word to the TX FIFO */
-
- data.w = *priv->buffer++;
- priv->remaining -= sizeof(uint32);
- }
- else
- {
- /* No.. transfer just the bytes remaining in the user buffer,
- * padding with zero as necessary to extend to a full word.
- */
-
- ubyte *ptr = (ubyte *)priv->remaining;
- int i;
-
- data.w = 0;
- for (i = 0; i < priv->remaining; i++)
- {
- data.b[i] = *ptr++;
- }
-
- /* Now the transfer is finished */
-
- priv->remaining = 0;
- }
-
- /* Put the word in the FIFO */
-
+
+static void stm32_sendfifo(struct stm32_dev_s *priv)
+{
+ union
+ {
+ uint32 w;
+ ubyte b[2];
+ } data;
+
+ /* Loop while there is more data to be sent and the RX FIFO is not full */
+
+ while (priv->remaining > 0 &&
+ (getreg32(STM32_SDIO_STA) & SDIO_STA_TXFIFOF) == 0)
+ {
+ /* Is there a full word remaining in the user buffer? */
+
+ if (priv->remaining >= sizeof(uint32))
+ {
+ /* Yes, transfer the word to the TX FIFO */
+
+ data.w = *priv->buffer++;
+ priv->remaining -= sizeof(uint32);
+ }
+ else
+ {
+ /* No.. transfer just the bytes remaining in the user buffer,
+ * padding with zero as necessary to extend to a full word.
+ */
+
+ ubyte *ptr = (ubyte *)priv->remaining;
+ int i;
+
+ data.w = 0;
+ for (i = 0; i < priv->remaining; i++)
+ {
+ data.b[i] = *ptr++;
+ }
+
+ /* Now the transfer is finished */
+
+ priv->remaining = 0;
+ }
+
+ /* Put the word in the FIFO */
+
putreg32(data.w, STM32_SDIO_FIFO);
}
-}
-
+}
+
/****************************************************************************
* Name: stm32_recvfifo
*
@@ -688,87 +694,87 @@ static void stm32_sendfifo(struct stm32_dev_s *priv)
* None
*
****************************************************************************/
-
-static void stm32_recvfifo(struct stm32_dev_s *priv)
-{
- union
- {
- uint32 w;
- ubyte b[2];
- } data;
-
- /* Loop while there is space to store the data and there is more
- * data available in the RX FIFO.
- */
-
- while (priv->remaining > 0 &&
- (getreg32(STM32_SDIO_STA) & SDIO_STA_RXDAVL) == 0)
- {
- /* Read the next word from the RX FIFO */
-
- data.w = getreg32(STM32_SDIO_FIFO);
- if (priv->remaining >= sizeof(uint32))
- {
- /* Transfer the whole word to the user buffer */
-
- *priv->buffer++ = data.w;
- priv->remaining -= sizeof(uint32);
- }
- else
- {
- /* Transfer any trailing fractional word */
-
- ubyte *ptr = (ubyte*)priv->buffer;
- int i;
-
- for (i = 0; i < priv->remaining; i++)
- {
- *ptr++ = data.b[i];
- }
-
- /* Now the transfer is finished */
-
- priv->remaining = 0;
- }
- }
-}
-
+
+static void stm32_recvfifo(struct stm32_dev_s *priv)
+{
+ union
+ {
+ uint32 w;
+ ubyte b[2];
+ } data;
+
+ /* Loop while there is space to store the data and there is more
+ * data available in the RX FIFO.
+ */
+
+ while (priv->remaining > 0 &&
+ (getreg32(STM32_SDIO_STA) & SDIO_STA_RXDAVL) == 0)
+ {
+ /* Read the next word from the RX FIFO */
+
+ data.w = getreg32(STM32_SDIO_FIFO);
+ if (priv->remaining >= sizeof(uint32))
+ {
+ /* Transfer the whole word to the user buffer */
+
+ *priv->buffer++ = data.w;
+ priv->remaining -= sizeof(uint32);
+ }
+ else
+ {
+ /* Transfer any trailing fractional word */
+
+ ubyte *ptr = (ubyte*)priv->buffer;
+ int i;
+
+ for (i = 0; i < priv->remaining; i++)
+ {
+ *ptr++ = data.b[i];
+ }
+
+ /* Now the transfer is finished */
+
+ priv->remaining = 0;
+ }
+ }
+}
+
/****************************************************************************
* Name: stm32_eventtimeout
*
* Description:
- * The watchdog timeout setup when the event wait start has expired without
+ * 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)
+ * argc - The number of arguments (should be 1)
* arg - The argument (state structure reference cast to uint32)
*
* Returned Value:
* None
*
- * Assumptions:
+ * 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);
- }
-}
-
+ ****************************************************************************/
+
+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
*
@@ -776,32 +782,32 @@ static void stm32_eventtimeout(int argc, uint32 arg)
* Wake up a waiting thread if the waited-for event has occurred.
*
* Input Parameters:
- * priv - An instance of the SDIO device interface
+ * priv - An instance of the SDIO device interface
* result - The result status of the transfer
*
* Returned Value:
* None
*
- * Assumptions:
+ * Assumptions:
* Always called from the interrupt level with interrupts disabled.
*
****************************************************************************/
-
-static void stm32_endwait(struct stm32_dev_s *priv, sdio_eventset_t wkupevent)
-{
- /* Cancel the watchdog timeout */
-
- (void)wd_cancel(priv->waitwdog);
-
- /* Disable event-related interrupts */
-
- stm32_configwaitints(priv, 0, 0, wkupevent);
-
- /* Wake up the waiting thread */
-
- stm32_givesem(priv);
-}
-
+
+static void stm32_endwait(struct stm32_dev_s *priv, sdio_eventset_t wkupevent)
+{
+ /* Cancel the watchdog timeout */
+
+ (void)wd_cancel(priv->waitwdog);
+
+ /* Disable event-related interrupts */
+
+ stm32_configwaitints(priv, 0, 0, wkupevent);
+
+ /* Wake up the waiting thread */
+
+ stm32_givesem(priv);
+}
+
/****************************************************************************
* Name: stm32_endtransfer
*
@@ -809,41 +815,41 @@ static void stm32_endwait(struct stm32_dev_s *priv, sdio_eventset_t wkupevent)
* Terminate a transfer with the provided status
*
* Input Parameters:
- * priv - An instance of the SDIO device interface
+ * priv - An instance of the SDIO device interface
* result - The result status of the transfer
*
* Returned Value:
- * None
- *
- * Assumptions:
+ * None
+ *
+ * Assumptions:
* Always called from the interrupt level with interrupts disabled.
*
****************************************************************************/
-
-static void stm32_endtransfer(struct stm32_dev_s *priv, int result)
-{
- /* Disable all transfer related interrupts */
-
- stm32_configxfrints(priv, 0);
-
- /* Mark the transfer finished with the provided status */
-
- priv->remaining = 0;
- priv->result = result;
-
- /* Is a data transfer complete event expected? */
-
- if ((priv->waitevents & SDIOWAIT_TRANSFERDONE) != 0)
- {
- /* Yes.. wake up any waiting threads */
-
- stm32_endwait(priv, SDIOWAIT_TRANSFERDONE);
- }
-}
-
+
+static void stm32_endtransfer(struct stm32_dev_s *priv, int result)
+{
+ /* Disable all transfer related interrupts */
+
+ stm32_configxfrints(priv, 0);
+
+ /* Mark the transfer finished with the provided status */
+
+ priv->remaining = 0;
+ priv->result = result;
+
+ /* Is a data transfer complete event expected? */
+
+ if ((priv->waitevents & SDIOWAIT_TRANSFERDONE) != 0)
+ {
+ /* Yes.. wake up any waiting threads */
+
+ stm32_endwait(priv, SDIOWAIT_TRANSFERDONE);
+ }
+}
+
/****************************************************************************
* Interrrupt Handling
- ****************************************************************************/
+ ****************************************************************************/
/****************************************************************************
* Name: stm32_interrupt
@@ -858,170 +864,170 @@ static void stm32_endtransfer(struct stm32_dev_s *priv, int result)
* None
*
****************************************************************************/
-
-static int stm32_interrupt(int irq, void *context)
-{
+
+static int stm32_interrupt(int irq, void *context)
+{
struct stm32_dev_s *priv = &g_sdiodev;
- uint32 enabled;
- uint32 pending;
-
- /* Loop while there are pending interrupts. Check the SDIO status
- * register. Mask out all bits that don't correspond to enabled
- * interrupts. (This depends on the fact that bits are ordered
- * the same in both the STA and MASK register). If there are non-zero
- * bits remaining, then we have work to do here.
- */
-
- while ((enabled = getreg32(STM32_SDIO_STA) & getreg32(STM32_SDIO_MASK)) != 0)
- {
- /* Handle in progress, interrupt driven data transfers ****************/
-
- pending = enabled & priv->xfrmask;
- if (pending != 0)
- {
+ uint32 enabled;
+ uint32 pending;
+
+ /* Loop while there are pending interrupts. Check the SDIO status
+ * register. Mask out all bits that don't correspond to enabled
+ * interrupts. (This depends on the fact that bits are ordered
+ * the same in both the STA and MASK register). If there are non-zero
+ * bits remaining, then we have work to do here.
+ */
+
+ while ((enabled = getreg32(STM32_SDIO_STA) & getreg32(STM32_SDIO_MASK)) != 0)
+ {
+ /* Handle in progress, interrupt driven data transfers ****************/
+
+ pending = enabled & priv->xfrmask;
+ if (pending != 0)
+ {
#ifdef CONFIG_SDIO_DMA
if (!priv->dmamode)
#endif
- {
- /* Is the RX FIFO half full or more? Is so then we must be
- * processing a receive transaction.
- */
+ {
+ /* Is the RX FIFO half full or more? Is so then we must be
+ * processing a receive transaction.
+ */
if ((pending & SDIO_STA_RXFIFOHF) != 0)
- {
- /* Receive data from the RX FIFO */
-
- stm32_recvfifo(priv);
- }
-
- /* Otherwise, Is the transmit FIFO half empty or less? If so we must
- * be processing a send transaction. NOTE: We can't be processing
- * both!
- */
+ {
+ /* Receive data from the RX FIFO */
+
+ stm32_recvfifo(priv);
+ }
+
+ /* Otherwise, Is the transmit FIFO half empty or less? If so we must
+ * be processing a send transaction. NOTE: We can't be processing
+ * both!
+ */
else if ((pending & SDIO_STA_TXFIFOHE) != 0)
- {
- /* Send data via the TX FIFO */
-
- stm32_sendfifo(priv);
+ {
+ /* Send data via the TX FIFO */
+
+ stm32_sendfifo(priv);
}
}
-
- /* Handle data end events */
-
+
+ /* Handle data end events */
+
if ((pending & SDIO_STA_DATAEND) != 0)
- {
- /* Handle any data remaining the RX FIFO. If the RX FIFO is
- * less than half full at the end of the transfer, then no
- * half-full interrupt will be received.
- */
+ {
+ /* Handle any data remaining the RX FIFO. If the RX FIFO is
+ * less than half full at the end of the transfer, then no
+ * half-full interrupt will be received.
+ */
#ifdef CONFIG_SDIO_DMA
if (!priv->dmamode)
-#endif
+#endif
{
- /* Receive data from the RX FIFO */
-
- stm32_recvfifo(priv);
+ /* Receive data from the RX FIFO */
+
+ stm32_recvfifo(priv);
}
-
- /* Then terminate the transfer */
-
- putreg32(SDIO_ICR_DATAENDC, STM32_SDIO_ICR);
+
+ /* Then terminate the transfer */
+
+ putreg32(SDIO_ICR_DATAENDC, STM32_SDIO_ICR);
stm32_endtransfer(priv, OK);
- }
-
- /* Handler data block send/receive CRC failure */
+ }
+
+ /* Handler data block send/receive CRC failure */
else if ((pending & SDIO_STA_DCRCFAIL) != 0)
- {
- /* Terminate the transfer with an error */
+ {
+ /* Terminate the transfer with an error */
putreg32(SDIO_ICR_DCRCFAILC, STM32_SDIO_ICR);
- stm32_endtransfer(priv, -EIO);
- }
-
- /* Handle data timeout error */
+ stm32_endtransfer(priv, -EIO);
+ }
+
+ /* Handle data timeout error */
else if ((pending & SDIO_STA_DTIMEOUT) != 0)
{
- /* Terminate the transfer with an error */
+ /* Terminate the transfer with an error */
putreg32(SDIO_ICR_DTIMEOUTC, STM32_SDIO_ICR);
- stm32_endtransfer(priv, -ETIMEDOUT);
- }
-
- /* Handle RX FIFO overrun error */
+ stm32_endtransfer(priv, -ETIMEDOUT);
+ }
+
+ /* Handle RX FIFO overrun error */
else if ((pending & SDIO_STA_RXOVERR) != 0)
{
- /* Terminate the transfer with an error */
+ /* Terminate the transfer with an error */
putreg32(SDIO_ICR_RXOVERRC, STM32_SDIO_ICR);
- stm32_endtransfer(priv, -EOVERFLOW);
- }
-
- /* Handle TX FIFO underrun error */
+ stm32_endtransfer(priv, -EOVERFLOW);
+ }
+
+ /* Handle TX FIFO underrun error */
else if ((pending & SDIO_STA_TXUNDERR) != 0)
{
- /* Terminate the transfer with an error */
+ /* Terminate the transfer with an error */
putreg32(SDIO_ICR_TXUNDERRC, STM32_SDIO_ICR);
- stm32_endtransfer(priv, -EOVERFLOW);
- }
-
- /* Handle start bit error */
+ stm32_endtransfer(priv, -EOVERFLOW);
+ }
+
+ /* Handle start bit error */
else if ((pending & SDIO_STA_STBITERR) != 0)
{
- /* Terminate the transfer with an error */
+ /* Terminate the transfer with an error */
putreg32(SDIO_ICR_STBITERRC, STM32_SDIO_ICR);
- stm32_endtransfer(priv, -EIO);
+ stm32_endtransfer(priv, -EIO);
}
- }
-
- /* Handle wait events *************************************************/
-
- pending = enabled & priv->waitmask;
- if (pending != 0)
- {
- /* Is this a response completion event? */
-
- if ((pending & SDIO_CRCRESP_STA) != 0)
- {
- /* Yes.. Is their a thread waiting for response done? */
-
- if ((priv->waitevents & SDIOWAIT_RESPONSEDONE) != 0)
- {
- /* Yes.. wake the thread up */
-
+ }
+
+ /* Handle wait events *************************************************/
+
+ pending = enabled & priv->waitmask;
+ if (pending != 0)
+ {
+ /* Is this a response completion event? */
+
+ if ((pending & SDIO_CRCRESP_STA) != 0)
+ {
+ /* Yes.. Is their a thread waiting for response done? */
+
+ if ((priv->waitevents & SDIOWAIT_RESPONSEDONE) != 0)
+ {
+ /* Yes.. wake the thread up */
+
putreg32(SDIO_CRCRESP_ICR, STM32_SDIO_ICR);
- stm32_endwait(priv, SDIOWAIT_RESPONSEDONE);
- }
- }
-
- /* Is this a command completion event? */
-
- if ((pending & SDIO_CMDDONE_STA) != 0)
- {
- /* Yes.. Is their a thread waiting for command done? */
-
- if ((priv->waitevents & SDIOWAIT_RESPONSEDONE) != 0)
- {
- /* Yes.. wake the thread up */
-
+ stm32_endwait(priv, SDIOWAIT_RESPONSEDONE);
+ }
+ }
+
+ /* Is this a command completion event? */
+
+ if ((pending & SDIO_CMDDONE_STA) != 0)
+ {
+ /* Yes.. Is their a thread waiting for command done? */
+
+ if ((priv->waitevents & SDIOWAIT_RESPONSEDONE) != 0)
+ {
+ /* Yes.. wake the thread up */
+
putreg32(SDIO_CMDDONE_ICR, STM32_SDIO_ICR);
- stm32_endwait(priv, SDIOWAIT_CMDDONE);
- }
- }
- }
- }
+ stm32_endwait(priv, SDIOWAIT_CMDDONE);
+ }
+ }
+ }
+ }
return OK;
-}
-
+}
+
/****************************************************************************
* SDIO Interface Methods
****************************************************************************/
@@ -1040,48 +1046,48 @@ 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 */
-
+{
+ 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
+ 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 */
-
+ stm32_setpwrctrl(SDIO_POWER_PWRCTRL_ON);
+
+ /* (Re-)enable clocking */
+
putreg32(1, SDIO_CLKCR_CLKEN_BB);
}
@@ -1100,8 +1106,8 @@ static void stm32_reset(FAR struct sdio_dev_s *dev)
****************************************************************************/
static ubyte stm32_status(FAR struct sdio_dev_s *dev)
-{
- struct stm32_dev_s *priv = (struct stm32_dev_s *)dev;
+{
+ struct stm32_dev_s *priv = (struct stm32_dev_s *)dev;
return priv->cdstatus;
}
@@ -1123,8 +1129,8 @@ static ubyte stm32_status(FAR struct sdio_dev_s *dev)
****************************************************************************/
static void stm32_widebus(FAR struct sdio_dev_s *dev, boolean wide)
-{
- struct stm32_dev_s *priv = (struct stm32_dev_s *)dev;
+{
+ struct stm32_dev_s *priv = (struct stm32_dev_s *)dev;
priv->widebus = wide;
}
@@ -1144,38 +1150,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 */
-
+{
+ 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);
-}
+ putreg32(1, SDIO_CLKCR_CLKEN_BB);
+}
/****************************************************************************
* Name: stm32_attach
@@ -1192,32 +1198,32 @@ static void stm32_clock(FAR struct sdio_dev_s *dev, enum sdio_clock_e rate)
****************************************************************************/
static int stm32_attach(FAR struct sdio_dev_s *dev)
-{
- int ret;
-
- /* Attach the SDIO interrupt handler */
-
- ret = irq_attach(STM32_IRQ_SDIO, stm32_interrupt);
- if (ret == OK)
- {
-
- /* Disable all interrupts at the SDIO controller and clear static
- * interrupt flags
- */
-
+{
+ int ret;
+
+ /* Attach the SDIO interrupt handler */
+
+ ret = irq_attach(STM32_IRQ_SDIO, stm32_interrupt);
+ if (ret == OK)
+ {
+
+ /* Disable all interrupts at the SDIO controller and clear static
+ * interrupt flags
+ */
+
putreg32(SDIO_MASK_RESET, STM32_SDIO_MASK);
putreg32(SDIO_ICR_STATICFLAGS, STM32_SDIO_ICR);
-
- /* Enable SDIO interrupts at the NVIC. They can now be enabled at
- * the SDIO controller as needed.
- */
-
- up_enable_irq(STM32_IRQ_SDIO);
-
- /* Set the interrrupt priority */
-
- up_prioritize_irq(STM32_IRQ_SDIO, CONFIG_SDIO_PRI);
- }
+
+ /* Enable SDIO interrupts at the NVIC. They can now be enabled at
+ * the SDIO controller as needed.
+ */
+
+ up_enable_irq(STM32_IRQ_SDIO);
+
+ /* Set the interrrupt priority */
+
+ up_prioritize_irq(STM32_IRQ_SDIO, CONFIG_SDIO_PRI);
+ }
return ret;
}
@@ -1286,178 +1292,178 @@ static void stm32_sendcmd(FAR struct sdio_dev_s *dev, uint32 cmd, uint32 arg)
putreg32(regval, STM32_SDIO_CMD);
}
-/****************************************************************************
- * Name: stm32_recvsetup
- *
- * Description:
- * Setup hardware in preparation for data trasfer from the card in non-DMA
- * (interrupt driven mode). This method will do whatever controller setup
- * is necessary. This would be called for SD memory just BEFORE sending
- * CMD13 (SEND_STATUS), CMD17 (READ_SINGLE_BLOCK), CMD18
- * (READ_MULTIPLE_BLOCKS), ACMD51 (SEND_SCR), etc. Normally, SDIO_WAITEVENT
- * will be called to receive the indication that the transfer is complete.
- *
- * Input Parameters:
- * dev - An instance of the SDIO device interface
- * buffer - Address of the buffer in which to receive the data
- * nbytes - The number of bytes in the transfer
- *
- * Returned Value:
- * Number of bytes sent on success; a negated errno on failure
- *
- ****************************************************************************/
-
-static int stm32_recvsetup(FAR struct sdio_dev_s *dev, FAR ubyte *buffer,
- size_t nbytes)
-{
+/****************************************************************************
+ * Name: stm32_recvsetup
+ *
+ * Description:
+ * Setup hardware in preparation for data trasfer from the card in non-DMA
+ * (interrupt driven mode). This method will do whatever controller setup
+ * is necessary. This would be called for SD memory just BEFORE sending
+ * CMD13 (SEND_STATUS), CMD17 (READ_SINGLE_BLOCK), CMD18
+ * (READ_MULTIPLE_BLOCKS), ACMD51 (SEND_SCR), etc. Normally, SDIO_WAITEVENT
+ * will be called to receive the indication that the transfer is complete.
+ *
+ * Input Parameters:
+ * dev - An instance of the SDIO device interface
+ * buffer - Address of the buffer in which to receive the data
+ * nbytes - The number of bytes in the transfer
+ *
+ * Returned Value:
+ * Number of bytes sent on success; a negated errno on failure
+ *
+ ****************************************************************************/
+
+static int stm32_recvsetup(FAR struct sdio_dev_s *dev, FAR ubyte *buffer,
+ size_t nbytes)
+{
struct stm32_dev_s *priv = (struct stm32_dev_s *)dev;
- uint32 dblocksize;
-
- DEBUGASSERT(priv != NULL && buffer != NULL && nbytes > 0);
- DEBUGASSERT(((uint32)buffer & 3) == 0);
-
- /* Reset the DPSM configuration */
-
+ uint32 dblocksize;
+
+ DEBUGASSERT(priv != NULL && buffer != NULL && nbytes > 0);
+ DEBUGASSERT(((uint32)buffer & 3) == 0);
+
+ /* Reset the DPSM configuration */
+
stm32_datadisable();
-
- /* Save the destination buffer information for use by the interrupt handler */
-
- priv->buffer = (uint32*)buffer;
- priv->remaining = nbytes;
- priv->result = -EBUSY;
-#ifdef CONFIG_SDIO_DMA
- priv->dmamode = FALSE;
-#endif
-
- /* Then set up the SDIO data path */
-
- dblocksize = stm32_log2(nbytes) << SDIO_DCTRL_DBLOCKSIZE_SHIFT;
- stm32_dataconfig(SDIO_DTIMER_DATATIMEOUT, nbytes, dblocksize|SDIO_DCTRL_DTDIR);
-
- /* And enable interrupts */
-
- stm32_configxfrints(priv, SDIO_RECV_MASK);
- return OK;
+
+ /* Save the destination buffer information for use by the interrupt handler */
+
+ priv->buffer = (uint32*)buffer;
+ priv->remaining = nbytes;
+ priv->result = -EBUSY;
+#ifdef CONFIG_SDIO_DMA
+ priv->dmamode = FALSE;
+#endif
+
+ /* Then set up the SDIO data path */
+
+ dblocksize = stm32_log2(nbytes) << SDIO_DCTRL_DBLOCKSIZE_SHIFT;
+ stm32_dataconfig(SDIO_DTIMER_DATATIMEOUT, nbytes, dblocksize|SDIO_DCTRL_DTDIR);
+
+ /* And enable interrupts */
+
+ stm32_configxfrints(priv, SDIO_RECV_MASK);
+ return OK;
}
-
-/****************************************************************************
- * Name: stm32_sendsetup
- *
- * Description:
- * Setup hardware in preparation for data trasfer from the card. This method
- * will do whatever controller setup is necessary. This would be called
- * for SD memory just AFTER sending CMD24 (WRITE_BLOCK), CMD25
- * (WRITE_MULTIPLE_BLOCK), ... and before SDIO_SENDDATA is called.
- *
- * Input Parameters:
- * dev - An instance of the SDIO device interface
- * buffer - Address of the buffer containing the data to send
- * nbytes - The number of bytes in the transfer
- *
- * Returned Value:
- * Number of bytes sent on success; a negated errno on failure
- *
- ****************************************************************************/
-
-static int stm32_sendsetup(FAR struct sdio_dev_s *dev, FAR const ubyte *buffer,
- size_t nbytes)
-{
+
+/****************************************************************************
+ * Name: stm32_sendsetup
+ *
+ * Description:
+ * Setup hardware in preparation for data trasfer from the card. This method
+ * will do whatever controller setup is necessary. This would be called
+ * for SD memory just AFTER sending CMD24 (WRITE_BLOCK), CMD25
+ * (WRITE_MULTIPLE_BLOCK), ... and before SDIO_SENDDATA is called.
+ *
+ * Input Parameters:
+ * dev - An instance of the SDIO device interface
+ * buffer - Address of the buffer containing the data to send
+ * nbytes - The number of bytes in the transfer
+ *
+ * Returned Value:
+ * Number of bytes sent on success; a negated errno on failure
+ *
+ ****************************************************************************/
+
+static int stm32_sendsetup(FAR struct sdio_dev_s *dev, FAR const ubyte *buffer,
+ size_t nbytes)
+{
struct stm32_dev_s *priv = (struct stm32_dev_s *)dev;
- uint32 dblocksize;
-
- DEBUGASSERT(priv != NULL && buffer != NULL && nbytes > 0);
- DEBUGASSERT(((uint32)buffer & 3) == 0);
-
- /* Reset the DPSM configuration */
-
+ uint32 dblocksize;
+
+ DEBUGASSERT(priv != NULL && buffer != NULL && nbytes > 0);
+ DEBUGASSERT(((uint32)buffer & 3) == 0);
+
+ /* Reset the DPSM configuration */
+
stm32_datadisable();
-
- /* Save the source buffer information for use by the interrupt handler */
-
- priv->buffer = (uint32*)buffer;
- priv->remaining = nbytes;
- priv->result = -EBUSY;
-#ifdef CONFIG_SDIO_DMA
- priv->dmamode = FALSE;
-#endif
-
- /* Then set up the SDIO data path */
-
- dblocksize = stm32_log2(nbytes) << SDIO_DCTRL_DBLOCKSIZE_SHIFT;
- stm32_dataconfig(SDIO_DTIMER_DATATIMEOUT, nbytes, dblocksize);
-
- /* Enable TX interrrupts */
-
- stm32_configxfrints(priv, SDIO_SEND_MASK);
- return OK;
+
+ /* Save the source buffer information for use by the interrupt handler */
+
+ priv->buffer = (uint32*)buffer;
+ priv->remaining = nbytes;
+ priv->result = -EBUSY;
+#ifdef CONFIG_SDIO_DMA
+ priv->dmamode = FALSE;
+#endif
+
+ /* Then set up the SDIO data path */
+
+ dblocksize = stm32_log2(nbytes) << SDIO_DCTRL_DBLOCKSIZE_SHIFT;
+ stm32_dataconfig(SDIO_DTIMER_DATATIMEOUT, nbytes, dblocksize);
+
+ /* Enable TX interrrupts */
+
+ stm32_configxfrints(priv, SDIO_SEND_MASK);
+ return OK;
}
-
-/****************************************************************************
- * Name: stm32_waitresponse
- *
- * Description:
- * Poll-wait for the response to the last command to be ready.
- *
- * Input Parameters:
- * dev - An instance of the SDIO device interface
- * cmd - The command that was sent. See 32-bit command definitions above.
- *
- * Returned Value:
- * OK is success; a negated errno on failure
- *
- ****************************************************************************/
-
-static int stm32_waitresponse(FAR struct sdio_dev_s *dev, uint32 cmd)
-{
- sint32 timeout;
- uint32 events;
-
- switch (cmd & MMCSD_RESPONSE_MASK)
- {
- case MMCSD_NO_RESPONSE:
- events = SDIO_CMDDONE_STA;
- timeout = SDIO_CMDTIMEOUT;
- break;
-
- case MMCSD_R1_RESPONSE:
- case MMCSD_R1B_RESPONSE:
- case MMCSD_R2_RESPONSE:
- case MMCSD_R6_RESPONSE:
- events = SDIO_CRCRESP_STA;
- timeout = SDIO_LONGTIMEOUT;
- break;
-
- case MMCSD_R4_RESPONSE:
- case MMCSD_R5_RESPONSE:
- return -ENOSYS;
-
- case MMCSD_R3_RESPONSE:
- case MMCSD_R7_RESPONSE:
- events = SDIO_RESPDONE_STA;
- timeout = SDIO_CMDTIMEOUT;
- break;
-
- default:
- return -EINVAL;
- }
-
- /* Then wait for the response (or timeout) */
-
+
+/****************************************************************************
+ * Name: stm32_waitresponse
+ *
+ * Description:
+ * Poll-wait for the response to the last command to be ready.
+ *
+ * Input Parameters:
+ * dev - An instance of the SDIO device interface
+ * cmd - The command that was sent. See 32-bit command definitions above.
+ *
+ * Returned Value:
+ * OK is success; a negated errno on failure
+ *
+ ****************************************************************************/
+
+static int stm32_waitresponse(FAR struct sdio_dev_s *dev, uint32 cmd)
+{
+ sint32 timeout;
+ uint32 events;
+
+ switch (cmd & MMCSD_RESPONSE_MASK)
+ {
+ case MMCSD_NO_RESPONSE:
+ events = SDIO_CMDDONE_STA;
+ timeout = SDIO_CMDTIMEOUT;
+ break;
+
+ case MMCSD_R1_RESPONSE:
+ case MMCSD_R1B_RESPONSE:
+ case MMCSD_R2_RESPONSE:
+ case MMCSD_R6_RESPONSE:
+ events = SDIO_CRCRESP_STA;
+ timeout = SDIO_LONGTIMEOUT;
+ break;
+
+ case MMCSD_R4_RESPONSE:
+ case MMCSD_R5_RESPONSE:
+ return -ENOSYS;
+
+ case MMCSD_R3_RESPONSE:
+ case MMCSD_R7_RESPONSE:
+ events = SDIO_RESPDONE_STA;
+ timeout = SDIO_CMDTIMEOUT;
+ break;
+
+ default:
+ return -EINVAL;
+ }
+
+ /* Then wait for the response (or timeout) */
+
while ((getreg32(STM32_SDIO_STA) & events) == 0)
{
- if (--timeout <= 0)
- {
- fdbg("ERROR: Timeout cmd=%04x\n", cmd);
- return -ETIMEDOUT;
+ if (--timeout <= 0)
+ {
+ fdbg("ERROR: Timeout cmd=%04x\n", cmd);
+ return -ETIMEDOUT;
}
}
-
- /* Clear all the static flags */
+
+ /* Clear all the static flags */
putreg32(SDIO_ICR_STATICFLAGS, STM32_SDIO_ICR);
return OK;
-}
-
+}
+
/****************************************************************************
* Name: stm32_recvRx
*
@@ -1667,8 +1673,8 @@ static int stm32_recvshort(FAR struct sdio_dev_s *dev, uint32 cmd, uint32 *rshor
}
return OK;
}
-
-/* MMC responses not supported */
+
+/* MMC responses not supported */
static int stm32_recvnotimpl(FAR struct sdio_dev_s *dev, uint32 cmd, uint32 *rnotimpl)
{
@@ -1679,16 +1685,16 @@ static int stm32_recvnotimpl(FAR struct sdio_dev_s *dev, uint32 cmd, uint32 *rno
* Name: stm32_waitenable
*
* 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_eventwait. This is done in this way
- * to help the driver to eliminate race conditions between the command
- * setup and the subsequent events.
- *
- * The enabled events persist until either (1) SDIO_WAITENABLE is called
- * again specifying a different set of wait events, or (2) SDIO_EVENTWAIT
- * returns.
- *
+ * 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_eventwait. This is done in this way
+ * to help the driver to eliminate race conditions between the command
+ * setup and the subsequent events.
+ *
+ * The enabled events persist until either (1) SDIO_WAITENABLE is called
+ * again specifying a different set of wait events, or (2) SDIO_EVENTWAIT
+ * returns.
+ *
* Input Parameters:
* dev - An instance of the SDIO device interface
* eventset - A bitset of events to enable or disable (see SDIOWAIT_*
@@ -1699,197 +1705,197 @@ static int stm32_recvnotimpl(FAR struct sdio_dev_s *dev, uint32 cmd, uint32 *rno
*
****************************************************************************/
-static void stm32_waitenable(FAR struct sdio_dev_s *dev,
+static void stm32_waitenable(FAR struct sdio_dev_s *dev,
sdio_eventset_t eventset)
-{
- struct stm32_dev_s *priv = (struct stm32_dev_s*)dev;
- uint32 waitmask;
-
- DEBUGASSERT(priv != NULL);
-
- /* Disable event-related interrupts */
-
- stm32_configwaitints(priv, 0, 0, 0);
-
- /* Select the interrupt mask that will give us the appropriate wakeup
- * interrupts.
- */
-
- waitmask = 0;
- if ((eventset & SDIOWAIT_CMDDONE) != 0)
- {
- waitmask |= SDIO_CMDDONE_MASK;
- }
-
- if ((eventset & SDIOWAIT_RESPONSEDONE) != 0)
- {
- waitmask |= SDIO_CRCRESP_MASK;
- }
-
- if ((eventset & SDIOWAIT_TRANSFERDONE) != 0)
- {
- waitmask |= SDIO_XFRDONE_MASK;
- }
-
- /* Enable event-related interrupts */
-
- putreg32(SDIO_WAITALL_ICR, STM32_SDIO_ICR);
- stm32_configwaitints(priv, waitmask, eventset, 0);
+{
+ struct stm32_dev_s *priv = (struct stm32_dev_s*)dev;
+ uint32 waitmask;
+
+ DEBUGASSERT(priv != NULL);
+
+ /* Disable event-related interrupts */
+
+ stm32_configwaitints(priv, 0, 0, 0);
+
+ /* Select the interrupt mask that will give us the appropriate wakeup
+ * interrupts.
+ */
+
+ waitmask = 0;
+ if ((eventset & SDIOWAIT_CMDDONE) != 0)
+ {
+ waitmask |= SDIO_CMDDONE_MASK;
+ }
+
+ if ((eventset & SDIOWAIT_RESPONSEDONE) != 0)
+ {
+ waitmask |= SDIO_CRCRESP_MASK;
+ }
+
+ if ((eventset & SDIOWAIT_TRANSFERDONE) != 0)
+ {
+ waitmask |= SDIO_XFRDONE_MASK;
+ }
+
+ /* Enable event-related interrupts */
+
+ putreg32(SDIO_WAITALL_ICR, STM32_SDIO_ICR);
+ stm32_configwaitints(priv, waitmask, eventset, 0);
}
/****************************************************************************
* Name: stm32_eventwait
*
* Description:
- * Wait for one of the enabled events to occur (or a timeout). Note that
- * all events enabled by SDIO_WAITEVENTS are disabled when stm32_eventwait
- * returns. SDIO_WAITEVENTS must be called again before stm32_eventwait
+ * Wait for one of the enabled events to occur (or a timeout). Note that
+ * all events enabled by SDIO_WAITEVENTS are disabled when stm32_eventwait
+ * returns. SDIO_WAITEVENTS must be called again before stm32_eventwait
* can be used again.
*
* Input Parameters:
* dev - An instance of the SDIO device interface
- * 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.
+ * 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. Should always
+ * Event set containing the event(s) that ended the wait. Should always
* be non-zero. All events are disabled after the wait concludes.
*
****************************************************************************/
-static sdio_eventset_t stm32_eventwait(FAR struct sdio_dev_s *dev,
+static sdio_eventset_t stm32_eventwait(FAR struct sdio_dev_s *dev,
uint32 timeout)
-{
- struct stm32_dev_s *priv = (struct stm32_dev_s*)dev;
- 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!
- */
-
- for (;;)
- {
- /* Wait for an event in event set to occur. If this the event has already
- * occurred, then the semaphore will already have been incremented and
- * there will be no wait.
- */
-
- stm32_takesem(priv);
-
- /* Check if the event has occurred. */
-
- wkupevent = (ubyte)(priv->wkupevent & priv->waitevents);
- if (wkupevent != 0)
- {
- /* Yes... break out of the loop with wkupevent non-zero */
-
- break;
- }
- }
-
- /* Disable event-related interrupts */
-
- stm32_configwaitints(priv, 0, 0, 0);
+{
+ struct stm32_dev_s *priv = (struct stm32_dev_s*)dev;
+ 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!
+ */
+
+ for (;;)
+ {
+ /* Wait for an event in event set to occur. If this the event has already
+ * occurred, then the semaphore will already have been incremented and
+ * there will be no wait.
+ */
+
+ stm32_takesem(priv);
+
+ /* Check if the event has occurred. */
+
+ wkupevent = (ubyte)(priv->wkupevent & priv->waitevents);
+ if (wkupevent != 0)
+ {
+ /* Yes... break out of the loop with wkupevent non-zero */
+
+ break;
+ }
+ }
+
+ /* Disable event-related interrupts */
+
+ stm32_configwaitints(priv, 0, 0, 0);
return wkupevent;
}
-/****************************************************************************
- * Name: stm32_callbackenable
- *
- * Description:
- * Enable/disable of a set of SDIO callback events. This is part of the
- * the SDIO callback sequence. The set of events is configured to enabled
- * callbacks to the function provided in stm32_registercallback.
- *
- * Events are automatically disabled once the callback is performed and no
- * further callback events will occur until they are again enabled by
- * calling this methos.
- *
- * Input Parameters:
- * dev - An instance of the SDIO device interface
+/****************************************************************************
+ * Name: stm32_callbackenable
+ *
+ * Description:
+ * Enable/disable of a set of SDIO callback events. This is part of the
+ * the SDIO callback sequence. The set of events is configured to enabled
+ * callbacks to the function provided in stm32_registercallback.
+ *
+ * Events are automatically disabled once the callback is performed and no
+ * further callback events will occur until they are again enabled by
+ * calling this methos.
+ *
+ * Input Parameters:
+ * dev - An instance of the SDIO device interface
* eventset - A bitset of events to enable or disable (see SDIOMEDIA_*
* definitions). 0=disable; 1=enable.
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
-static void stm32_callbackenable(FAR struct sdio_dev_s *dev,
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void stm32_callbackenable(FAR struct sdio_dev_s *dev,
sdio_eventset_t eventset)
-{
- struct stm32_dev_s *priv = (struct stm32_dev_s*)dev;
- DEBUGASSERT(priv != NULL);
- priv->cbevents = eventset;
+{
+ struct stm32_dev_s *priv = (struct stm32_dev_s*)dev;
+ DEBUGASSERT(priv != NULL);
+ priv->cbevents = eventset;
stm32_callback(priv);
}
-
-/****************************************************************************
- * Name: stm32_registercallback
- *
- * Description:
- * Register a callback that that will be invoked on any media status
- * change. Callbacks should not be made from interrupt handlers, rather
- * interrupt level events should be handled by calling back on the work
- * thread.
- *
- * When this method is called, all callbacks should be disabled until they
- * are enabled via a call to SDIO_CALLBACKENABLE
- *
- * Input Parameters:
- * dev - Device-specific state data
- * callback - The funtion to call on the media change
- * arg - A caller provided value to return with the callback
- *
- * Returned Value:
- * 0 on success; negated errno on failure.
- *
- ****************************************************************************/
-
-static int stm32_registercallback(FAR struct sdio_dev_s *dev,
- sdio_mediachange_t callback, void *arg)
-{
- struct stm32_dev_s *priv = (struct stm32_dev_s*)dev;
-
- /* Disable callbacks and register this callback and is argument */
-
- DEBUGASSERT(priv != NULL);
- priv->cbevents = 0;
- priv->cbarg = arg;
+
+/****************************************************************************
+ * Name: stm32_registercallback
+ *
+ * Description:
+ * Register a callback that that will be invoked on any media status
+ * change. Callbacks should not be made from interrupt handlers, rather
+ * interrupt level events should be handled by calling back on the work
+ * thread.
+ *
+ * When this method is called, all callbacks should be disabled until they
+ * are enabled via a call to SDIO_CALLBACKENABLE
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * callback - The funtion to call on the media change
+ * arg - A caller provided value to return with the callback
+ *
+ * Returned Value:
+ * 0 on success; negated errno on failure.
+ *
+ ****************************************************************************/
+
+static int stm32_registercallback(FAR struct sdio_dev_s *dev,
+ worker_t callback, void *arg)
+{
+ struct stm32_dev_s *priv = (struct stm32_dev_s*)dev;
+
+ /* Disable callbacks and register this callback and is argument */
+
+ DEBUGASSERT(priv != NULL);
+ priv->cbevents = 0;
+ priv->cbarg = arg;
priv->callback = callback;
- return OK;
-}
-
+ return OK;
+}
+
/****************************************************************************
* Name: stm32_dmasupported
*
@@ -1915,15 +1921,15 @@ static boolean stm32_dmasupported(FAR struct sdio_dev_s *dev)
* Name: stm32_dmarecvsetup
*
* Description:
- * Setup to perform a read DMA. If the processor supports a data cache,
- * then this method will also make sure that the contents of the DMA memory
- * and the data cache are coherent. For read transfers this may mean
- * invalidating the data cache.
+ * Setup to perform a read DMA. If the processor supports a data cache,
+ * then this method will also make sure that the contents of the DMA memory
+ * and the data cache are coherent. For read transfers this may mean
+ * invalidating the data cache.
*
* Input Parameters:
* dev - An instance of the SDIO device interface
* buffer - The memory to DMA from
- * buflen - The size of the DMA transfer in bytes
+ * buflen - The size of the DMA transfer in bytes
*
* Returned Value:
* OK on success; a negated errno on failure
@@ -1931,50 +1937,50 @@ static boolean stm32_dmasupported(FAR struct sdio_dev_s *dev)
****************************************************************************/
#ifdef CONFIG_SDIO_DMA
-static int stm32_dmarecvsetup(FAR struct sdio_dev_s *dev, FAR ubyte *buffer,
+static int stm32_dmarecvsetup(FAR struct sdio_dev_s *dev, FAR ubyte *buffer,
size_t buflen)
{
struct stm32_dev_s *priv = (struct stm32_dev_s *)dev;
- uint32 dblocksize;
- int ret = -EINVAL;
-
- DEBUGASSERT(priv != NULL && buffer != NULL && buflen > 0);
- DEBUGASSERT(((uint32)buffer & 3) == 0);
-
- /* Reset the DPSM configuration */
-
+ uint32 dblocksize;
+ int ret = -EINVAL;
+
+ DEBUGASSERT(priv != NULL && buffer != NULL && buflen > 0);
+ DEBUGASSERT(((uint32)buffer & 3) == 0);
+
+ /* Reset the DPSM configuration */
+
stm32_datadisable();
-
- /* Wide bus operation is required for DMA */
-
- if (priv->widebus)
- {
- /* Save the destination buffer information for use by the interrupt handler */
-
- priv->buffer = (uint32*)buffer;
- priv->remaining = buflen;
- priv->result = -EBUSY;
- priv->dmamode = TRUE;
-
- /* Then set up the SDIO data path */
-
- dblocksize = stm32_log2(buflen) << SDIO_DCTRL_DBLOCKSIZE_SHIFT;
- stm32_dataconfig(SDIO_DTIMER_DATATIMEOUT, buflen, dblocksize|SDIO_DCTRL_DTDIR);
-
- /* Configure the RX DMA */
-
- stm32_configxfrints(priv, SDIO_DMARECV_MASK);
+
+ /* Wide bus operation is required for DMA */
+
+ if (priv->widebus)
+ {
+ /* Save the destination buffer information for use by the interrupt handler */
+
+ priv->buffer = (uint32*)buffer;
+ priv->remaining = buflen;
+ priv->result = -EBUSY;
+ priv->dmamode = TRUE;
+
+ /* Then set up the SDIO data path */
+
+ dblocksize = stm32_log2(buflen) << SDIO_DCTRL_DBLOCKSIZE_SHIFT;
+ stm32_dataconfig(SDIO_DTIMER_DATATIMEOUT, buflen, dblocksize|SDIO_DCTRL_DTDIR);
+
+ /* Configure the RX DMA */
+
+ stm32_configxfrints(priv, SDIO_DMARECV_MASK);
putreg32(1, SDIO_DCTRL_DMAEN_BB);
- stm32_dmasetup(priv->dma, STM32_SDIO_FIFO, (uint32)buffer,
- (buflen + 3) >> 2, SDIO_RXDMA16_CONFIG);
-
- /* Start the DMA */
-
- stm32_dmastart(priv->dma, stm32_dmacallback, priv, FALSE);
- ret = OK;
- }
- return ret;
+ stm32_dmasetup(priv->dma, STM32_SDIO_FIFO, (uint32)buffer,
+ (buflen + 3) >> 2, SDIO_RXDMA16_CONFIG);
+
+ /* Start the DMA */
+
+ stm32_dmastart(priv->dma, stm32_dmacallback, priv, FALSE);
+ ret = OK;
+ }
+ return ret;
}
#endif
@@ -1982,15 +1988,15 @@ static int stm32_dmarecvsetup(FAR struct sdio_dev_s *dev, FAR ubyte *buffer,
* Name: stm32_dmasendsetup
*
* Description:
- * Setup to perform a write DMA. If the processor supports a data cache,
- * then this method will also make sure that the contents of the DMA memory
- * and the data cache are coherent. For write transfers, this may mean
- * flushing the data cache.
+ * Setup to perform a write DMA. If the processor supports a data cache,
+ * then this method will also make sure that the contents of the DMA memory
+ * and the data cache are coherent. For write transfers, this may mean
+ * flushing the data cache.
*
* Input Parameters:
* dev - An instance of the SDIO device interface
* buffer - The memory to DMA into
- * buflen - The size of the DMA transfer in bytes
+ * buflen - The size of the DMA transfer in bytes
*
* Returned Value:
* OK on success; a negated errno on failure
@@ -2002,47 +2008,47 @@ static int stm32_dmasendsetup(FAR struct sdio_dev_s *dev,
FAR const ubyte *buffer, size_t buflen)
{
struct stm32_dev_s *priv = (struct stm32_dev_s *)dev;
- uint32 dblocksize;
- int ret = -EINVAL;
-
- DEBUGASSERT(priv != NULL && buffer != NULL && buflen > 0);
- DEBUGASSERT(((uint32)buffer & 3) == 0);
-
- /* Reset the DPSM configuration */
-
+ uint32 dblocksize;
+ int ret = -EINVAL;
+
+ DEBUGASSERT(priv != NULL && buffer != NULL && buflen > 0);
+ DEBUGASSERT(((uint32)buffer & 3) == 0);
+
+ /* Reset the DPSM configuration */
+
stm32_datadisable();
-
- /* Wide bus operation is required for DMA */
-
- if (priv->widebus)
- {
- /* Save the source buffer information for use by the interrupt handler */
-
- priv->buffer = (uint32*)buffer;
- priv->remaining = buflen;
- priv->result = -EBUSY;
- priv->dmamode = TRUE;
-
- /* Then set up the SDIO data path */
-
- dblocksize = stm32_log2(buflen) << SDIO_DCTRL_DBLOCKSIZE_SHIFT;
- stm32_dataconfig(SDIO_DTIMER_DATATIMEOUT, buflen, dblocksize);
-
- /* Enable TX interrrupts */
-
- stm32_configxfrints(priv, SDIO_DMASEND_MASK);
-
- /* Configure the TX DMA */
-
- stm32_dmasetup(priv->dma, STM32_SDIO_FIFO, (uint32)buffer,
- (buflen + 3) >> 2, SDIO_TXDMA16_CONFIG);
- putreg32(1, SDIO_DCTRL_DMAEN_BB);
-
- /* Start the DMA */
-
- stm32_dmastart(priv->dma, stm32_dmacallback, priv, FALSE);
- ret = OK;
- }
+
+ /* Wide bus operation is required for DMA */
+
+ if (priv->widebus)
+ {
+ /* Save the source buffer information for use by the interrupt handler */
+
+ priv->buffer = (uint32*)buffer;
+ priv->remaining = buflen;
+ priv->result = -EBUSY;
+ priv->dmamode = TRUE;
+
+ /* Then set up the SDIO data path */
+
+ dblocksize = stm32_log2(buflen) << SDIO_DCTRL_DBLOCKSIZE_SHIFT;
+ stm32_dataconfig(SDIO_DTIMER_DATATIMEOUT, buflen, dblocksize);
+
+ /* Enable TX interrrupts */
+
+ stm32_configxfrints(priv, SDIO_DMASEND_MASK);
+
+ /* Configure the TX DMA */
+
+ stm32_dmasetup(priv->dma, STM32_SDIO_FIFO, (uint32)buffer,
+ (buflen + 3) >> 2, SDIO_TXDMA16_CONFIG);
+ putreg32(1, SDIO_DCTRL_DMAEN_BB);
+
+ /* Start the DMA */
+
+ stm32_dmastart(priv->dma, stm32_dmacallback, priv, FALSE);
+ ret = OK;
+ }
return ret;
}
#endif
@@ -2054,58 +2060,74 @@ static int stm32_dmasendsetup(FAR struct sdio_dev_s *dev,
* Name: stm32_callback
*
* Description:
- * Perform callback.
- *
- * Assumptions:
- * This function does not execute in the context of an interrupt handler.
- * It may be invoked on any user thread or scheduled on the work thread
+ * Perform callback.
+ *
+ * Assumptions:
+ * This function does not execute in the context of an interrupt handler.
+ * It may be invoked on any user thread or scheduled on the work thread
* from an interrupt handler.
*
****************************************************************************/
-static void stm32_callback(void *arg)
-{
- struct stm32_dev_s *priv = (struct stm32_dev_s*)arg;
-
- /* Is a callback registered? */
-
- DEBUGASSERT(priv != NULL);
- if (priv->callback)
- {
- /* Yes.. Check for enabled callback events */
-
- if ((stm32_status(&priv->dev) & SDIO_STATUS_PRESENT) != 0)
- {
- /* Media is present. Is the media inserted event enabled? */
-
- if ((priv->cbevents & SDIOMEDIA_INSERTED) == 0)
- {
- /* No... return without performing the callback */
-
- return;
- }
- }
- else
- {
- /* Media is not present. Is the media eject event enabled? */
-
- if ((priv->cbevents & SDIOMEDIA_EJECTED) == 0)
- {
- /* No... return without performing the callback */
-
- return;
- }
- }
-
- /* Perform the callback, disabling further callbacks. Of course, the
- * the callback can (and probably should) re-enable callbacks.
- */
-
- priv->cbevents = 0;
- priv->callback(priv->cbarg);
- }
+static void stm32_callback(void *arg)
+{
+ struct stm32_dev_s *priv = (struct stm32_dev_s*)arg;
+
+ /* Is a callback registered? */
+
+ DEBUGASSERT(priv != NULL);
+ if (priv->callback)
+ {
+ /* Yes.. Check for enabled callback events */
+
+ if ((stm32_status(&priv->dev) & SDIO_STATUS_PRESENT) != 0)
+ {
+ /* Media is present. Is the media inserted event enabled? */
+
+ if ((priv->cbevents & SDIOMEDIA_INSERTED) == 0)
+ {
+ /* No... return without performing the callback */
+
+ return;
+ }
+ }
+ else
+ {
+ /* Media is not present. Is the media eject event enabled? */
+
+ if ((priv->cbevents & SDIOMEDIA_EJECTED) == 0)
+ {
+ /* No... return without performing the callback */
+
+ return;
+ }
+ }
+
+ /* Perform the callback, disabling further callbacks. Of course, the
+ * the callback can (and probably should) re-enable callbacks.
+ */
+ priv->cbevents = 0;
+
+ /* Callbacks cannot be performed in the context of an interrupt handler.
+ * If we are in an interrupt handler, then queue the callback to be
+ * performed later on the work thread.
+ */
+
+ if (up_interrupt_context())
+ {
+ /* Yes.. queue it */
+
+ (void)work_queue(&priv->cbwork, (worker_t)priv->callback, priv->cbarg, 0);
+ }
+ else
+ {
+ /* No.. then just call the callback here */
+
+ priv->callback(priv->cbarg);
+ }
+ }
}
-
+
/****************************************************************************
* Name: stm32_default
*
@@ -2137,31 +2159,31 @@ static void stm32_default(void)
* Description:
* Initialize SDIO for operation.
*
- * Input Parameters:
- * slotno - Not used.
- *
- * Returned Values:
- * A reference to an SDIO interface structure. NULL is returned on failures.
+ * Input Parameters:
+ * slotno - Not used.
+ *
+ * Returned Values:
+ * A reference to an SDIO interface structure. NULL is returned on failures.
*
****************************************************************************/
FAR struct sdio_dev_s *sdio_initialize(int slotno)
-{
- /* 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 */
-
-#ifdef CONFIG_SDIO_DMA
- priv->dma = stm32_dmachannel(DMACHAN_SDIO);
-#endif
+{
+ /* 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 */
+
+#ifdef CONFIG_SDIO_DMA
+ priv->dma = stm32_dmachannel(DMACHAN_SDIO);
+#endif
/* Configure GPIOs for 4-bit, wide-bus operation (the chip is capable of
* 8-bit wide bus operation but D4-D7 are not configured).
@@ -2172,12 +2194,12 @@ 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);
-
- /* Reset the card and assure that it is in the initial, unconfigured
- * state.
+ 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;
}
@@ -2185,82 +2207,82 @@ 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
+ * 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
+ * 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
*
****************************************************************************/
-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;
-
- /* Update card status */
-
- 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);
+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;
+
+ /* Update card status */
+
+ 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.
+ * 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.
*
- * Input Parameters:
- * dev - An instance of the SDIO driver device state structure.
- * wrprotect - TRUE is a card is writeprotected.
- *
- * Returned Values:
- * None
+ * 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);
+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 */
+#endif /* CONFIG_STM32_SDIO */
diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt
index eb1a2878e..6ccd83664 100644
--- a/nuttx/configs/README.txt
+++ b/nuttx/configs/README.txt
@@ -333,6 +333,14 @@ defconfig -- This is a configuration file similar to the Linux
CONFIG_MMCSD_SPICLOCK - Maximum SPI clock to drive MMC/SD card.
Default is 20MHz.
+ SDIO-based MMC/SD driver
+ CONFIG_FS_READAHEAD - Enable read-ahead buffering
+ CONFIG_FS_WRITEBUFFER - Enable write buffering
+ CONFIG_SDIO_DMA - SDIO driver supports DMA
+ CONFIG_MMCSD_MMCSUPPORT - Enable support for MMC cards
+ CONFIG_MMCSD_HAVECARDDETECT - SDIO driver card detection is
+ 100% accurate
+
TCP/IP and UDP support via uIP
CONFIG_NET - Enable or disable all network features
CONFIG_NET_IPv6 - Build in support for IPv6
diff --git a/nuttx/configs/stm3210e-eval/README.txt b/nuttx/configs/stm3210e-eval/README.txt
index 46ee8fb4f..b6eb981df 100755
--- a/nuttx/configs/stm3210e-eval/README.txt
+++ b/nuttx/configs/stm3210e-eval/README.txt
@@ -382,6 +382,12 @@ STM3210E-EVAL-specific Configuration Options
CONFIG_STM32_SPI_DMA - Use DMA to improve SPI transfer performance.
Cannot be used with CONFIG_STM32_SPI_INTERRUPT.
+ CONFIG_SDIO_DMA - Support DMA data transfers. Requires CONFIG_STM32_SDIO
+ and CONFIG_STM32_DMA2.
+ CONFIG_SDIO_PRI - Select SDIO interrupt prority. Default: Medium
+ CONFIG_SDIO_DMAPRIO - Select SDIO DMA interrupt priority.
+ Default: Medium
+
Configurations
^^^^^^^^^^^^^^
diff --git a/nuttx/configs/stm3210e-eval/RIDE/defconfig b/nuttx/configs/stm3210e-eval/RIDE/defconfig
index 3f7bfec5a..7e9a52b64 100755
--- a/nuttx/configs/stm3210e-eval/RIDE/defconfig
+++ b/nuttx/configs/stm3210e-eval/RIDE/defconfig
@@ -294,6 +294,24 @@ CONFIG_HAVE_LIBM=n
# CONFIG_NXFLAT. Enable support for the NXFLAT binary format.
# This format will support execution of NuttX binaries located
# in a ROMFS filesystem (see examples/nxflat).
+# CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to
+# handle delayed processing from interrupt handlers. This feature
+# is required for some drivers but, if there are not complaints,
+# can be safely disabled. The worker thread also performs
+# garbage collection -- completing any delayed memory deallocations
+# from interrupt handlers. If the worker thread is disabled,
+# then that clean will be performed by the IDLE thread instead
+# (which runs at the lowest of priority and may not be appropriate
+# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE
+# is enabled, then the following options can also be used:
+# CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker
+# thread. Default: 50
+# CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for
+# work. Default: 50 MS.
+# CONFIG_SCHED_WORKSTACKSIZE - The stack size allocated for the worker
+# thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
+# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
+# the worker thread. Default: 4
#
CONFIG_EXAMPLE=null
CONFIG_DEBUG=n
@@ -320,6 +338,11 @@ CONFIG_FDCLONE_DISABLE=n
CONFIG_FDCLONE_STDIO=n
CONFIG_SDCLONE_DISABLE=y
CONFIG_NXFLAT=n
+CONFIG_SCHED_WORKQUEUE=n
+CONFIG_SCHED_WORKPRIORITY=50
+CONFIG_SCHED_WORKPERIOD=50
+CONFIG_SCHED_WORKSTACKSIZE=1024
+CONFIG_SIG_SIGWORK=4
#
# The following can be used to disable categories of
@@ -445,6 +468,31 @@ CONFIG_MMCSD_READONLY=n
CONFIG_MMCSD_SPICLOCK=12500000
#
+# Block driver buffering
+#
+# CONFIG_FS_READAHEAD
+# Enable read-ahead buffering
+# CONFIG_FS_WRITEBUFFER
+# Enable write buffering
+#
+CONFIG_FS_READAHEAD=n
+CONFIG_FS_WRITEBUFFER=n
+
+#
+# SDIO-based MMC/SD driver
+#
+# CONFIG_SDIO_DMA
+# SDIO driver supports DMA
+# CONFIG_MMCSD_MMCSUPPORT
+# Enable support for MMC cards
+# CONFIG_MMCSD_HAVECARDDETECT
+# SDIO driver card detection is 100% accurate
+#
+CONFIG_SDIO_DMA=n
+CONFIG_MMCSD_MMCSUPPORT=n
+CONFIG_MMCSD_HAVECARDDETECT=n
+
+#
# TCP/IP and UDP support via uIP
# CONFIG_NET - Enable or disable all network features
# CONFIG_NET_IPv6 - Build in support for IPv6
@@ -563,7 +611,6 @@ CONFIG_USBSER_VENDORSTR="Nuttx"
CONFIG_USBSER_PRODUCTSTR="USBdev Serial"
CONFIG_USBSER_RXBUFSIZE=512
CONFIG_USBSER_TXBUFSIZE=512
-CONFIG_NXFLAT=n
#
# USB Storage Device Configuration
diff --git a/nuttx/configs/stm3210e-eval/nsh/defconfig b/nuttx/configs/stm3210e-eval/nsh/defconfig
index a3d22defd..19f682d90 100755
--- a/nuttx/configs/stm3210e-eval/nsh/defconfig
+++ b/nuttx/configs/stm3210e-eval/nsh/defconfig
@@ -101,10 +101,10 @@ CONFIG_STM32_DFU=y
# Individual subsystems can be enabled:
# AHB:
CONFIG_STM32_DMA1=n
-CONFIG_STM32_DMA2=n
+CONFIG_STM32_DMA2=y
CONFIG_STM32_CRC=n
CONFIG_STM32_FSMC=y
-CONFIG_STM32_SDIO=n
+CONFIG_STM32_SDIO=y
# APB1:
CONFIG_STM32_TIM2=n
CONFIG_STM32_TIM3=n
@@ -304,6 +304,24 @@ CONFIG_HAVE_LIBM=n
# CONFIG_NXFLAT. Enable support for the NXFLAT binary format.
# This format will support execution of NuttX binaries located
# in a ROMFS filesystem (see examples/nxflat).
+# CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to
+# handle delayed processing from interrupt handlers. This feature
+# is required for some drivers but, if there are not complaints,
+# can be safely disabled. The worker thread also performs
+# garbage collection -- completing any delayed memory deallocations
+# from interrupt handlers. If the worker thread is disabled,
+# then that clean will be performed by the IDLE thread instead
+# (which runs at the lowest of priority and may not be appropriate
+# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE
+# is enabled, then the following options can also be used:
+# CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker
+# thread. Default: 50
+# CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for
+# work. Default: 50 MS.
+# CONFIG_SCHED_WORKSTACKSIZE - The stack size allocated for the worker
+# thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
+# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
+# the worker thread. Default: 4
#
CONFIG_EXAMPLE=nsh
CONFIG_DEBUG=n
@@ -329,6 +347,11 @@ CONFIG_FDCLONE_DISABLE=n
CONFIG_FDCLONE_STDIO=n
CONFIG_SDCLONE_DISABLE=y
CONFIG_NXFLAT=n
+CONFIG_SCHED_WORKQUEUE=y
+CONFIG_SCHED_WORKPRIORITY=50
+CONFIG_SCHED_WORKPERIOD=50
+CONFIG_SCHED_WORKSTACKSIZE=1024
+CONFIG_SIG_SIGWORK=4
#
# The following can be used to disable categories of
@@ -454,6 +477,31 @@ CONFIG_MMCSD_READONLY=n
CONFIG_MMCSD_SPICLOCK=12500000
#
+# Block driver buffering
+#
+# CONFIG_FS_READAHEAD
+# Enable read-ahead buffering
+# CONFIG_FS_WRITEBUFFER
+# Enable write buffering
+#
+CONFIG_FS_READAHEAD=n
+CONFIG_FS_WRITEBUFFER=n
+
+#
+# SDIO-based MMC/SD driver
+#
+# CONFIG_SDIO_DMA
+# SDIO driver supports DMA
+# CONFIG_MMCSD_MMCSUPPORT
+# Enable support for MMC cards
+# CONFIG_MMCSD_HAVECARDDETECT
+# SDIO driver card detection is 100% accurate
+#
+CONFIG_SDIO_DMA=n
+CONFIG_MMCSD_MMCSUPPORT=n
+CONFIG_MMCSD_HAVECARDDETECT=n
+
+#
# TCP/IP and UDP support via uIP
# CONFIG_NET - Enable or disable all network features
# CONFIG_NET_IPv6 - Build in support for IPv6
@@ -572,7 +620,6 @@ CONFIG_USBSER_VENDORSTR="Nuttx"
CONFIG_USBSER_PRODUCTSTR="USBdev Serial"
CONFIG_USBSER_RXBUFSIZE=512
CONFIG_USBSER_TXBUFSIZE=512
-CONFIG_NXFLAT=n
#
# USB Storage Device Configuration
diff --git a/nuttx/configs/stm3210e-eval/ostest/defconfig b/nuttx/configs/stm3210e-eval/ostest/defconfig
index 1d18778fe..45e416804 100755
--- a/nuttx/configs/stm3210e-eval/ostest/defconfig
+++ b/nuttx/configs/stm3210e-eval/ostest/defconfig
@@ -306,6 +306,24 @@ CONFIG_HAVE_LIBM=n
# CONFIG_NXFLAT. Enable support for the NXFLAT binary format.
# This format will support execution of NuttX binaries located
# in a ROMFS filesystem (see examples/nxflat).
+# CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to
+# handle delayed processing from interrupt handlers. This feature
+# is required for some drivers but, if there are not complaints,
+# can be safely disabled. The worker thread also performs
+# garbage collection -- completing any delayed memory deallocations
+# from interrupt handlers. If the worker thread is disabled,
+# then that clean will be performed by the IDLE thread instead
+# (which runs at the lowest of priority and may not be appropriate
+# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE
+# is enabled, then the following options can also be used:
+# CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker
+# thread. Default: 50
+# CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for
+# work. Default: 50 MS.
+# CONFIG_SCHED_WORKSTACKSIZE - The stack size allocated for the worker
+# thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
+# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
+# the worker thread. Default: 4
#
CONFIG_EXAMPLE=ostest
CONFIG_DEBUG=n
@@ -331,6 +349,11 @@ CONFIG_FDCLONE_DISABLE=n
CONFIG_FDCLONE_STDIO=n
CONFIG_SDCLONE_DISABLE=y
CONFIG_NXFLAT=n
+CONFIG_SCHED_WORKQUEUE=n
+CONFIG_SCHED_WORKPRIORITY=50
+CONFIG_SCHED_WORKPERIOD=50
+CONFIG_SCHED_WORKSTACKSIZE=1024
+CONFIG_SIG_SIGWORK=4
#
# The following can be used to disable categories of
@@ -456,6 +479,31 @@ CONFIG_MMCSD_READONLY=n
CONFIG_MMCSD_SPICLOCK=12500000
#
+# Block driver buffering
+#
+# CONFIG_FS_READAHEAD
+# Enable read-ahead buffering
+# CONFIG_FS_WRITEBUFFER
+# Enable write buffering
+#
+CONFIG_FS_READAHEAD=n
+CONFIG_FS_WRITEBUFFER=n
+
+#
+# SDIO-based MMC/SD driver
+#
+# CONFIG_SDIO_DMA
+# SDIO driver supports DMA
+# CONFIG_MMCSD_MMCSUPPORT
+# Enable support for MMC cards
+# CONFIG_MMCSD_HAVECARDDETECT
+# SDIO driver card detection is 100% accurate
+#
+CONFIG_SDIO_DMA=n
+CONFIG_MMCSD_MMCSUPPORT=n
+CONFIG_MMCSD_HAVECARDDETECT=n
+
+#
# TCP/IP and UDP support via uIP
# CONFIG_NET - Enable or disable all network features
# CONFIG_NET_IPv6 - Build in support for IPv6
@@ -574,7 +622,6 @@ CONFIG_USBSER_VENDORSTR="Nuttx"
CONFIG_USBSER_PRODUCTSTR="USBdev Serial"
CONFIG_USBSER_RXBUFSIZE=512
CONFIG_USBSER_TXBUFSIZE=512
-CONFIG_NXFLAT=n
#
# USB Storage Device Configuration
diff --git a/nuttx/configs/stm3210e-eval/usbserial/defconfig b/nuttx/configs/stm3210e-eval/usbserial/defconfig
index 0917bc2f1..6d7adf0c0 100755
--- a/nuttx/configs/stm3210e-eval/usbserial/defconfig
+++ b/nuttx/configs/stm3210e-eval/usbserial/defconfig
@@ -306,6 +306,24 @@ CONFIG_HAVE_LIBM=n
# CONFIG_NXFLAT. Enable support for the NXFLAT binary format.
# This format will support execution of NuttX binaries located
# in a ROMFS filesystem (see examples/nxflat).
+# CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to
+# handle delayed processing from interrupt handlers. This feature
+# is required for some drivers but, if there are not complaints,
+# can be safely disabled. The worker thread also performs
+# garbage collection -- completing any delayed memory deallocations
+# from interrupt handlers. If the worker thread is disabled,
+# then that clean will be performed by the IDLE thread instead
+# (which runs at the lowest of priority and may not be appropriate
+# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE
+# is enabled, then the following options can also be used:
+# CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker
+# thread. Default: 50
+# CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for
+# work. Default: 50 MS.
+# CONFIG_SCHED_WORKSTACKSIZE - The stack size allocated for the worker
+# thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
+# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
+# the worker thread. Default: 4
#
CONFIG_EXAMPLE=usbserial
CONFIG_DEBUG=n
@@ -332,6 +350,11 @@ CONFIG_FDCLONE_DISABLE=n
CONFIG_FDCLONE_STDIO=n
CONFIG_SDCLONE_DISABLE=y
CONFIG_NXFLAT=n
+CONFIG_SCHED_WORKQUEUE=n
+CONFIG_SCHED_WORKPRIORITY=50
+CONFIG_SCHED_WORKPERIOD=50
+CONFIG_SCHED_WORKSTACKSIZE=1024
+CONFIG_SIG_SIGWORK=4
#
# The following can be used to disable categories of
@@ -457,6 +480,31 @@ CONFIG_MMCSD_READONLY=n
CONFIG_MMCSD_SPICLOCK=12500000
#
+# Block driver buffering
+#
+# CONFIG_FS_READAHEAD
+# Enable read-ahead buffering
+# CONFIG_FS_WRITEBUFFER
+# Enable write buffering
+#
+CONFIG_FS_READAHEAD=n
+CONFIG_FS_WRITEBUFFER=n
+
+#
+# SDIO-based MMC/SD driver
+#
+# CONFIG_SDIO_DMA
+# SDIO driver supports DMA
+# CONFIG_MMCSD_MMCSUPPORT
+# Enable support for MMC cards
+# CONFIG_MMCSD_HAVECARDDETECT
+# SDIO driver card detection is 100% accurate
+#
+CONFIG_SDIO_DMA=n
+CONFIG_MMCSD_MMCSUPPORT=n
+CONFIG_MMCSD_HAVECARDDETECT=n
+
+#
# TCP/IP and UDP support via uIP
# CONFIG_NET - Enable or disable all network features
# CONFIG_NET_IPv6 - Build in support for IPv6
@@ -575,7 +623,6 @@ CONFIG_USBSER_VENDORSTR="Nuttx"
CONFIG_USBSER_PRODUCTSTR="USBdev Serial"
CONFIG_USBSER_RXBUFSIZE=512
CONFIG_USBSER_TXBUFSIZE=512
-CONFIG_NXFLAT=n
#
# USB Storage Device Configuration
diff --git a/nuttx/drivers/mmcsd/mmcsd_sdio.c b/nuttx/drivers/mmcsd/mmcsd_sdio.c
index 1a3016e88..97c2a6dc0 100644
--- a/nuttx/drivers/mmcsd/mmcsd_sdio.c
+++ b/nuttx/drivers/mmcsd/mmcsd_sdio.c
@@ -944,13 +944,13 @@ static int mmcsd_verifystate(FAR struct mmcsd_state_s *priv, uint32 state)
* Transfer Helpers
****************************************************************************/
-/****************************************************************************
- * Name: mmcsd_wrprotected
- *
- * Description:
+/****************************************************************************
+ * 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)
@@ -964,12 +964,12 @@ static boolean mmcsd_wrprotected(FAR struct mmcsd_state_s *priv)
return (priv->wrprotect || priv->locked || SDIO_WRPROTECTED(priv->dev));
}
-/****************************************************************************
- * Name: mmcsd_eventwait
- *
- * Description:
- * Wait for the specified events to occur. Check for wakeup on error events.
- *
+/****************************************************************************
+ * 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,
@@ -1001,14 +1001,14 @@ static int mmcsd_eventwait(FAR struct mmcsd_state_s *priv,
return OK;
}
-/****************************************************************************
- * Name: mmcsd_transferready
- *
- * Description:
+/****************************************************************************
+ * Name: mmcsd_transferready
+ *
+ * Description:
* Check if the MMC/SD card is ready for the next read or write transfer.
* Ready means: (1) card still in the slot, and (2) if the last transfer
- * was a write transfer, the card is no longer busy from that transfer.
- *
+ * was a write transfer, the card is no longer busy from that transfer.
+ *
****************************************************************************/
static int mmcsd_transferready(FAR struct mmcsd_state_s *priv)
@@ -1095,27 +1095,27 @@ static int mmcsd_transferready(FAR struct mmcsd_state_s *priv)
return -ETIMEDOUT;
}
-/****************************************************************************
- * Name: mmcsd_stoptransmission
- *
- * Description:
- * Send STOP_TRANSMISSION
- *
+/****************************************************************************
+ * Name: mmcsd_stoptransmission
+ *
+ * Description:
+ * Send STOP_TRANSMISSION
+ *
****************************************************************************/
-
+
static int mmcsd_stoptransmission(FAR struct mmcsd_state_s *priv)
{
- int ret;
-
- /* Send CMD12, STOP_TRANSMISSION, and verify good R1 return status */
+ int ret;
+
+ /* Send CMD12, STOP_TRANSMISSION, and verify good R1 return status */
- mmcsd_sendcmdpoll(priv, MMCSD_CMD12, 0);
+ mmcsd_sendcmdpoll(priv, MMCSD_CMD12, 0);
ret = mmcsd_recvR1(priv, MMCSD_CMD12);
if (ret != OK)
{
fdbg("ERROR: mmcsd_recvR1 for CMD12 failed: %d\n", ret);
- }
- return ret;
+ }
+ return ret;
}
/****************************************************************************
@@ -1139,16 +1139,16 @@ static int mmcsd_setblocklen(FAR struct mmcsd_state_s *priv, uint32 blocklen)
* block length is specified in the CSD.
*/
- mmcsd_sendcmdpoll(priv, MMCSD_CMD16, priv->blocksize);
- ret = mmcsd_recvR1(priv, MMCSD_CMD16);
- if (ret == OK)
+ mmcsd_sendcmdpoll(priv, MMCSD_CMD16, priv->blocksize);
+ ret = mmcsd_recvR1(priv, MMCSD_CMD16);
+ if (ret == OK)
{
priv->selblocklen = blocklen;
}
else
{
- fdbg("ERROR: mmcsd_recvR1 for CMD16 failed: %d\n", ret);
- }
+ fdbg("ERROR: mmcsd_recvR1 for CMD16 failed: %d\n", ret);
+ }
}
return ret;
@@ -1172,12 +1172,12 @@ static ssize_t mmcsd_readsingle(FAR struct mmcsd_state_s *priv,
DEBUGASSERT(priv != NULL && buffer != NULL);
/* Check if the card is locked */
-
- if (priv->locked)
+
+ if (priv->locked)
{
- fdbg("ERROR: Card is locked\n");
- return -EPERM;
- }
+ fdbg("ERROR: Card is locked\n");
+ return -EPERM;
+ }
/* Verify that the card is ready for the transfer. The card may still be
* busy from the preceding write transfer. It would be simpler to check
@@ -1207,28 +1207,28 @@ static ssize_t mmcsd_readsingle(FAR struct mmcsd_state_s *priv,
}
fvdbg("offset=%d\n", offset);
- /* Select the block size for the card */
+ /* Select the block size for the card */
ret = mmcsd_setblocklen(priv, priv->blocksize);
- if (ret != OK)
+ if (ret != OK)
{
- fdbg("ERROR: mmcsd_setblocklen failed: %d\n", ret);
- return ret;
- }
+ fdbg("ERROR: mmcsd_setblocklen failed: %d\n", ret);
+ return ret;
+ }
/* Configure SDIO controller hardware for the read transfer */
SDIO_WAITENABLE(priv->dev, SDIOWAIT_TRANSFERDONE|SDIOWAIT_TIMEOUT);
-#ifdef CONFIG_SDIO_DMA
+#ifdef CONFIG_SDIO_DMA
if (priv->dma)
- {
+ {
SDIO_DMARECVSETUP(priv->dev, buffer, priv->blocksize);
}
else
-#endif
- {
+#endif
+ {
SDIO_RECVSETUP(priv->dev, buffer, priv->blocksize);
- }
+ }
/* Send CMD17, READ_SINGLE_BLOCK: Read a block of the size selected
* by the mmcsd_setblocklen() and verify that good R1 status is
@@ -1236,19 +1236,19 @@ static ssize_t mmcsd_readsingle(FAR struct mmcsd_state_s *priv,
* state.
*/
- mmcsd_sendcmdpoll(priv, MMCSD_CMD17, offset);
- ret = mmcsd_recvR1(priv, MMCSD_CMD17);
- if (ret != OK)
- {
+ mmcsd_sendcmdpoll(priv, MMCSD_CMD17, offset);
+ ret = mmcsd_recvR1(priv, MMCSD_CMD17);
+ if (ret != OK)
+ {
fdbg("ERROR: mmcsd_recvR1 for CMD17 failed: %d\n", ret);
- return ret;
+ return ret;
}
/* Then wait for the data transfer to complete */
- ret = mmcsd_eventwait(priv, SDIOWAIT_TIMEOUT, MMCSD_BLOCK_DATADELAY);
- if (ret != OK)
- {
+ ret = mmcsd_eventwait(priv, SDIOWAIT_TIMEOUT, MMCSD_BLOCK_DATADELAY);
+ if (ret != OK)
+ {
fdbg("ERROR: CMD17 transfer failed: %d\n", ret);
}
return ret;
@@ -1274,12 +1274,12 @@ static ssize_t mmcsd_readmultiple(FAR struct mmcsd_state_s *priv,
DEBUGASSERT(priv != NULL && buffer != NULL && nblocks > 1);
/* Check if the card is locked */
-
- if (priv->locked)
+
+ if (priv->locked)
{
- fdbg("ERROR: Card is locked\n");
- return -EPERM;
- }
+ fdbg("ERROR: Card is locked\n");
+ return -EPERM;
+ }
/* Verify that the card is ready for the transfer. The card may still be
* busy from the preceding write transfer. It would be simpler to check
@@ -1310,48 +1310,48 @@ static ssize_t mmcsd_readmultiple(FAR struct mmcsd_state_s *priv,
}
fvdbg("nbytes=%d byte offset=%d\n", nbytes, offset);
- /* Select the block size for the card */
+ /* Select the block size for the card */
ret = mmcsd_setblocklen(priv, priv->blocksize);
- if (ret != OK)
+ if (ret != OK)
{
- fdbg("ERROR: mmcsd_setblocklen failed: %d\n", ret);
- return ret;
- }
+ fdbg("ERROR: mmcsd_setblocklen failed: %d\n", ret);
+ return ret;
+ }
/* Configure SDIO controller hardware for the read transfer */
SDIO_WAITENABLE(priv->dev, SDIOWAIT_TRANSFERDONE|SDIOWAIT_TIMEOUT);
-#ifdef CONFIG_SDIO_DMA
+#ifdef CONFIG_SDIO_DMA
if (priv->dma)
- {
+ {
SDIO_DMARECVSETUP(priv->dev, buffer, nbytes);
}
else
-#endif
- {
+#endif
+ {
SDIO_RECVSETUP(priv->dev, buffer, nbytes);
- }
-
+ }
+
/* Send CMD18, READ_MULT_BLOCK: Read a block of the size selected by
* the mmcsd_setblocklen() and verify that good R1 status is returned
*/
mmcsd_sendcmdpoll(priv, MMCSD_CMD18, offset);
ret = mmcsd_recvR1(priv, MMCSD_CMD18);
- if (ret != OK)
- {
+ if (ret != OK)
+ {
fdbg("ERROR: mmcsd_recvR1 for CMD18 failed: %d\n", ret);
- return ret;
+ return ret;
}
/* Wait for the transfer to complete */
ret = mmcsd_eventwait(priv, SDIOWAIT_TIMEOUT, nblocks * MMCSD_BLOCK_DATADELAY);
- if (ret != OK)
- {
+ if (ret != OK)
+ {
fdbg("ERROR: CMD18 transfer failed: %d\n", ret);
- return ret;
+ return ret;
}
/* Send STOP_TRANSMISSION */
@@ -1414,12 +1414,12 @@ static ssize_t mmcsd_writesingle(FAR struct mmcsd_state_s *priv,
/* Check if the card is locked or write protected (either via software or
* via the mechanical write protect on the card)
*/
-
- if (mmcsd_wrprotected(priv))
+
+ if (mmcsd_wrprotected(priv))
{
- fdbg("ERROR: Card is locked or write protected\n");
- return -EPERM;
- }
+ fdbg("ERROR: Card is locked or write protected\n");
+ return -EPERM;
+ }
/* Verify that the card is ready for the transfer. The card may still be
* busy from the preceding write transfer. It would be simpler to check
@@ -1449,13 +1449,13 @@ static ssize_t mmcsd_writesingle(FAR struct mmcsd_state_s *priv,
}
fvdbg("offset=%d\n", offset);
- /* Select the block size for the card */
+ /* Select the block size for the card */
ret = mmcsd_setblocklen(priv, priv->blocksize);
- if (ret != OK)
+ if (ret != OK)
{
- fdbg("ERROR: mmcsd_setblocklen failed: %d\n", ret);
- return ret;
+ fdbg("ERROR: mmcsd_setblocklen failed: %d\n", ret);
+ return ret;
}
/* Send CMD24, WRITE_BLOCK, and verify that good R1 status is returned */
@@ -1464,29 +1464,29 @@ static ssize_t mmcsd_writesingle(FAR struct mmcsd_state_s *priv,
ret = mmcsd_recvR1(priv, MMCSD_CMD24);
if (ret != OK)
{
- fdbg("ERROR: mmcsd_recvR1 for CMD24 failed: %d\n", ret);
- return ret;
+ fdbg("ERROR: mmcsd_recvR1 for CMD24 failed: %d\n", ret);
+ return ret;
}
-
+
/* Configure SDIO controller hardware for the write transfer */
SDIO_WAITENABLE(priv->dev, SDIOWAIT_TRANSFERDONE|SDIOWAIT_TIMEOUT);
-#ifdef CONFIG_SDIO_DMA
+#ifdef CONFIG_SDIO_DMA
if (priv->dma)
- {
- SDIO_DMASENDSETUP(priv->dev, buffer, priv->blocksize);
+ {
+ SDIO_DMASENDSETUP(priv->dev, buffer, priv->blocksize);
}
else
-#endif
- {
- SDIO_SENDSETUP(priv->dev, buffer, priv->blocksize);
- }
+#endif
+ {
+ SDIO_SENDSETUP(priv->dev, buffer, priv->blocksize);
+ }
/* Wait for the transfer to complete */
- ret = mmcsd_eventwait(priv, SDIOWAIT_TIMEOUT, MMCSD_BLOCK_DATADELAY);
- if (ret != OK)
- {
+ ret = mmcsd_eventwait(priv, SDIOWAIT_TIMEOUT, MMCSD_BLOCK_DATADELAY);
+ if (ret != OK)
+ {
fdbg("ERROR: CMD24 transfer failed: %d\n", ret);
}
@@ -1520,12 +1520,12 @@ static ssize_t mmcsd_writemultiple(FAR struct mmcsd_state_s *priv,
/* Check if the card is locked or write protected (either via software or
* via the mechanical write protect on the card)
*/
-
- if (mmcsd_wrprotected(priv))
+
+ if (mmcsd_wrprotected(priv))
{
- fdbg("ERROR: Card is locked or write protected\n");
- return -EPERM;
- }
+ fdbg("ERROR: Card is locked or write protected\n");
+ return -EPERM;
+ }
/* Verify that the card is ready for the transfer. The card may still be
* busy from the preceding write transfer. It would be simpler to check
@@ -1556,13 +1556,13 @@ static ssize_t mmcsd_writemultiple(FAR struct mmcsd_state_s *priv,
}
fvdbg("nbytes=%d byte offset=%d\n", nbytes, offset);
- /* Select the block size for the card */
+ /* Select the block size for the card */
ret = mmcsd_setblocklen(priv, priv->blocksize);
- if (ret != OK)
+ if (ret != OK)
{
- fdbg("ERROR: mmcsd_setblocklen failed: %d\n", ret);
- return ret;
+ fdbg("ERROR: mmcsd_setblocklen failed: %d\n", ret);
+ return ret;
}
/* If this is an SD card, then send ACMD23 (SET_WR_BLK_COUNT) just before
@@ -1573,14 +1573,14 @@ static ssize_t mmcsd_writemultiple(FAR struct mmcsd_state_s *priv,
if (IS_SD(priv->type))
{
- /* Send CMD55, APP_CMD, a verify that good R1 status is retured */
-
+ /* Send CMD55, APP_CMD, a verify that good R1 status is retured */
+
mmcsd_sendcmdpoll(priv, SD_CMD55, 0);
ret = mmcsd_recvR1(priv, SD_CMD55);
if (ret != OK)
{
- fdbg("ERROR: mmcsd_recvR1 for CMD55 (ACMD23) failed: %d\n", ret);
- return ret;
+ fdbg("ERROR: mmcsd_recvR1 for CMD55 (ACMD23) failed: %d\n", ret);
+ return ret;
}
/* Send CMD23, SET_WR_BLK_COUNT, and verify that good R1 status is returned */
@@ -1589,8 +1589,8 @@ static ssize_t mmcsd_writemultiple(FAR struct mmcsd_state_s *priv,
ret = mmcsd_recvR1(priv, SD_ACMD23);
if (ret != OK)
{
- fdbg("ERROR: mmcsd_recvR1 for ACMD23 failed: %d\n", ret);
- return ret;
+ fdbg("ERROR: mmcsd_recvR1 for ACMD23 failed: %d\n", ret);
+ return ret;
}
}
@@ -1602,31 +1602,31 @@ static ssize_t mmcsd_writemultiple(FAR struct mmcsd_state_s *priv,
ret = mmcsd_recvR1(priv, MMCSD_CMD25);
if (ret != OK)
{
- fdbg("ERROR: mmcsd_recvR1 for CMD24 failed: %d\n", ret);
- return ret;
+ fdbg("ERROR: mmcsd_recvR1 for CMD24 failed: %d\n", ret);
+ return ret;
}
-
+
/* Configure SDIO controller hardware for the write transfer */
SDIO_WAITENABLE(priv->dev, SDIOWAIT_TRANSFERDONE|SDIOWAIT_TIMEOUT);
-#ifdef CONFIG_SDIO_DMA
+#ifdef CONFIG_SDIO_DMA
if (priv->dma)
- {
- SDIO_DMASENDSETUP(priv->dev, buffer, nbytes);
+ {
+ SDIO_DMASENDSETUP(priv->dev, buffer, nbytes);
}
else
-#endif
- {
- SDIO_SENDSETUP(priv->dev, buffer, nbytes);
- }
+#endif
+ {
+ SDIO_SENDSETUP(priv->dev, buffer, nbytes);
+ }
/* Wait for the transfer to complete */
ret =mmcsd_eventwait(priv, SDIOWAIT_TIMEOUT, nblocks * MMCSD_BLOCK_DATADELAY);
- if (ret != OK)
- {
+ if (ret != OK)
+ {
fdbg("ERROR: CMD18 transfer failed: %d\n", ret);
- return ret;
+ return ret;
}
/* Send STOP_TRANSMISSION */
@@ -1951,7 +1951,8 @@ static void mmcsd_mediachange(FAR void *arg)
if (SDIO_PRESENT(priv->dev))
{
/* No... process the card insertion. This could cause chaos if we think
- * that a card is already present and there are mounted filesystms!
+ * that a card is already present and there are mounted filesystems!
+ * NOTE that mmcsd_probe() will always re-enable callbacks appropriately.
*/
(void)mmcsd_probe(priv);
@@ -1959,7 +1960,8 @@ static void mmcsd_mediachange(FAR void *arg)
else
{
/* No... process the card removal. This could have very bad implications
- * for any mounted file systems!
+ * for any mounted file systems! NOTE that mmcsd_removed() does NOT
+ * re-enable callbacks so we will need to do that here.
*/
(void)mmcsd_removed(priv);
diff --git a/nuttx/include/nuttx/sdio.h b/nuttx/include/nuttx/sdio.h
index 23dc3d458..dacd6ef47 100755
--- a/nuttx/include/nuttx/sdio.h
+++ b/nuttx/include/nuttx/sdio.h
@@ -42,6 +42,7 @@
#include <nuttx/config.h>
#include <sys/types.h>
+#include <nuttx/wqueue.h>
/****************************************************************************
* Pre-Processor Definitions
@@ -505,8 +506,8 @@
*
* Input Parameters:
* dev - An instance of the SDIO device interface
- * eventset - A bitset of events to enable or disable (see SDIOWAIT_*
- * definitions). 0=disable; 1=enable.
+ * eventset - A bitset of events to enable or disable (see SDIOWAIT_*
+ * definitions). 0=disable; 1=enable.
*
* Returned Value:
* None
@@ -532,7 +533,7 @@
*
* Returned Value:
* Event set containing the event(s) that ended the wait. Should always
- * be non-zero. All events are disabled after the wait concludes.
+ * be non-zero. All events are disabled after the wait concludes.
*
****************************************************************************/
@@ -552,8 +553,8 @@
*
* Input Parameters:
* dev - An instance of the SDIO device interface
- * eventset - A bitset of events to enable or disable (see SDIOMEDIA_*
- * definitions). 0=disable; 1=enable.
+ * eventset - A bitset of events to enable or disable (see SDIOMEDIA_*
+ * definitions). 0=disable; 1=enable.
*
* Returned Value:
* None
@@ -660,10 +661,6 @@
* Public Types
****************************************************************************/
-/* The type of the media change callback function */
-
-typedef void (*sdio_mediachange_t)(FAR void *arg);
-
/* Various clocking used by the SDIO driver */
enum sdio_clock_e
@@ -727,7 +724,7 @@ struct sdio_dev_s
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);
+ worker_t callback, void *arg);
/* DMA */
diff --git a/nuttx/include/nuttx/wqueue.h b/nuttx/include/nuttx/wqueue.h
index c44af7ed5..238fb1722 100755
--- a/nuttx/include/nuttx/wqueue.h
+++ b/nuttx/include/nuttx/wqueue.h
@@ -45,8 +45,6 @@
#include <signal.h>
#include <queue.h>
-#ifdef CONFIG_SCHED_WORKQUEUE
-
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
@@ -166,5 +164,4 @@ EXTERN int work_cancel(struct work_s *work);
#endif
#endif /* __ASSEMBLY__ */
-#endif /* CONFIG_SCHED_WORKQUEUE */
#endif /* __INCLUDE_NUTTX_WQUEUE_H */
diff --git a/nuttx/sched/work_internal.h b/nuttx/sched/work_internal.h
index 90f9e4ba1..c0b371b73 100755
--- a/nuttx/sched/work_internal.h
+++ b/nuttx/sched/work_internal.h
@@ -56,7 +56,7 @@
# define CONFIG_SCHED_WORKPRIORITY 50
#endif
-#ifndef CONFIG_SCHED_WORKPERIODUS
+#ifndef CONFIG_SCHED_WORKPERIOD
# define CONFIG_SCHED_WORKPERIOD (50*1000) /* 50 milliseconds */
#endif