Add logic to STM32 SDIO driver to terminate on a DMA error

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4408 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
patacongo 2012-02-21 15:17:42 +00:00
parent 070f707e7d
commit cb971e195e
4 changed files with 70 additions and 13 deletions

View File

@ -45,6 +45,8 @@
#include "chip.h"
/* Include the correct DMA register definitions for this STM32 family */
#if defined(CONFIG_STM32_STM32F10XX)
# include "chip/stm32f10xxx_dma.h"
#elif defined(CONFIG_STM32_STM32F40XX)
@ -53,12 +55,50 @@
# error "Unknown STM32 DMA"
#endif
/* These definitions provide the bit encoding of the 'status' parameter passed to the
* DMA callback function (see dma_callback_t).
*/
#if defined(CONFIG_STM32_STM32F10XX)
# define DMA_STATUS_FEIF 0
# define DMA_STATUS_DMEIF 0
# define DMA_STATUS_TEIF DMA_CHAN_TEIF_BIT /* Channel Transfer Error */
# define DMA_STATUS_HTIF DMA_CHAN_HTIF_BIT /* Channel Half Transfer */
# define DMA_STATUS_TCIF DMA_CHAN_TCIF_BIT /* Channel Transfer Complete */
#elif defined(CONFIG_STM32_STM32F40XX)
# define DMA_STATUS_FEIF DMA_STREAM_FEIF_BIT /* Stream FIFO error */
# define DMA_STATUS_DMEIF DMA_STREAM_DMEIF_BIT /* Stream direct mode error */
# define DMA_STATUS_TEIF DMA_STREAM_TEIF_BIT /* Stream Transfer Error */
# define DMA_STATUS_HTIF DMA_STREAM_HTIF_BIT /* Stream Half Transfer */
# define DMA_STATUS_TCIF DMA_STREAM_TCIF_BIT /* Stream Transfer Complete */
#endif
#define DMA_STATUS_ERROR (DMA_STATUS_FEIF|DMA_STATUS_DMEIF|DMA_STATUS_TEIF)
#define DMA_STATUS_SUCCESS (DMA_STATUS_TCIF|DMA_STATUS_HTIF)
/************************************************************************************
* Public Types
************************************************************************************/
/* DMA_HANDLE provides an opaque are reference that can be used to represent a DMA
* channel (F1) or a DMA stream (F4).
*/
typedef FAR void *DMA_HANDLE;
typedef void (*dma_callback_t)(DMA_HANDLE handle, uint8_t isr, void *arg);
/* Description:
* This is the type of the callback that is used to inform the user of the the
* completion of the DMA.
*
* Input Parameters:
* handle - Refers tot he DMA channel or stream
* status - A bit encoded value that provides the completion status. See the
* DMASTATUS_* definitions above.
* arg - A user-provided value that was provided when stm32_dmastart() was
* called.
*/
typedef void (*dma_callback_t)(DMA_HANDLE handle, uint8_t status, void *arg);
#ifdef CONFIG_DEBUG_DMA
#if defined(CONFIG_STM32_STM32F10XX)

View File

@ -401,7 +401,7 @@ static void stm32_dumpsamples(struct stm32_dev_s *priv);
#endif
#ifdef CONFIG_SDIO_DMA
static void stm32_dmacallback(DMA_HANDLE handle, uint8_t isr, void *arg);
static void stm32_dmacallback(DMA_HANDLE handle, uint8_t status, void *arg);
#endif
/* Data Transfer Helpers ****************************************************/
@ -856,25 +856,42 @@ static void stm32_dumpsamples(struct stm32_dev_s *priv)
****************************************************************************/
#ifdef CONFIG_SDIO_DMA
static void stm32_dmacallback(DMA_HANDLE handle, uint8_t isr, void *arg)
static void stm32_dmacallback(DMA_HANDLE handle, uint8_t status, void *arg)
{
FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)arg;
DEBUGASSERT(priv->dmamode);
sdio_eventset_t result;
/* The SDIO appears to handle the End-Of-Transfer interrupt first with the
* End-Of-DMA event occurring significantly later.
/* In the normal case, SDIO appears to handle the End-Of-Transfer interrupt
* first with the End-Of-DMA event occurring significantly later. On
* transfer errors, however, the DMA error will occur before the End-of-
* Transfer.
*/
stm32_sample((struct stm32_dev_s*)arg, SAMPLENDX_DMA_CALLBACK);
/* Then terminate the transfer (we should already have the SDIO transfer
* done interrupt. If not, the transfer will appropriately time out).
/* Get the result of the DMA transfer */
if ((status & DMA_STATUS_ERROR) != 0)
{
flldbg("DMA error %02x, remaining: %d\n", status, priv->remaining);
result = SDIOWAIT_ERROR;
}
else
{
result = SDIOWAIT_TRANSFERDONE;
}
/* Then terminate the transfer if this completes all of the steps in the
* transfer OR if a DMA error occurred. In the non-error case, we should
* already have the SDIO transfer done interrupt. If not, the transfer
* will appropriately time out.
*/
priv->xfrflags |= SDIO_DMADONE_FLAG;
if (priv->xfrflags == SDIO_ALLDONE)
if (priv->xfrflags == SDIO_ALLDONE || result == SDIOWAIT_ERROR)
{
stm32_endtransfer(priv, SDIOWAIT_TRANSFERDONE);
stm32_endtransfer(priv, result);
}
}
#endif

View File

@ -587,7 +587,7 @@ Where <subdir> is one of the following:
CONFIG_DEBUG_PWM
1. This example supports the Quadrature Encode test (apps/examples/qencoder)
2. This example supports the Quadrature Encode test (apps/examples/qencoder)
but this must be manually enabled by selecting:
CONFIG_QENCODER=y : Enable the generic Quadrature Encoder infrastructure

View File

@ -1,8 +1,8 @@
/****************************************************************************
* include/nuttx/sdio.h
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions