SAMA5: Add DMA suppport (untested)

This commit is contained in:
Gregory Nutt 2013-08-04 10:44:18 -06:00
parent a93b095ce4
commit 8194e6bbcf
7 changed files with 2267 additions and 9 deletions

View File

@ -95,18 +95,26 @@
# define ATSAMA5D3 1 /* SAMA5D3 family */
# define SAM_ISRAM0_SIZE (64*1024) /* 128KB of SRAM in two banks */
# define SAM_ISRAM1_SIZE (64*1024)
# define SAM_NDMAC 2 /* (2) DMA controllers */
# define SAM_NDMACHAN 8 /* (8) DMA channels per DMA controller */
#elif defined(CONFIG_ARCH_CHIP_ATSAMA5D33)
# define ATSAMA5D3 1 /* SAMA5D3 family */
# define SAM_ISRAM0_SIZE (64*1024) /* 128KB of SRAM in two banks */
# define SAM_ISRAM1_SIZE (64*1024)
# define SAM_NDMAC 2 /* (2) DMA controllers */
# define SAM_NDMACHAN 8 /* (8) DMA channels per DMA controller */
#elif defined(CONFIG_ARCH_CHIP_ATSAMA5D34)
# define ATSAMA5D3 1 /* SAMA5D3 family */
# define SAM_ISRAM0_SIZE (64*1024) /* 128KB of SRAM in two banks */
# define SAM_ISRAM1_SIZE (64*1024)
# define SAM_NDMAC 2 /* (2) DMA controllers */
# define SAM_NDMACHAN 8 /* (8) DMA channels per DMA controller */
#elif defined(CONFIG_ARCH_CHIP_ATSAMA5D35)
# define ATSAMA5D3 1 /* SAMA5D3 family */
# define SAM_ISRAM0_SIZE (64*1024) /* 128KB of SRAM in two banks */
# define SAM_ISRAM1_SIZE (64*1024)
# define SAM_NDMAC 2 /* (2) DMA controllers */
# define SAM_NDMACHAN 8 /* (8) DMA channels per DMA controller */
#else
# error Unrecognized SAMAD5 chip
#endif

View File

@ -1,5 +1,5 @@
/****************************************************************************
* arch/arm/src/sam34-ek/sam3u_dmac.c
* arch/arm/src/sam34/sam3u_dmac.c
*
* Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -72,7 +72,7 @@
/* If AT90SAM3U support is enabled, then OS DMA support should also be enabled */
#ifndef CONFIG_ARCH_DMA
# warning "ATSAM3U DMA enabled but CONFIG_ARCH_DMA disabled"
# warning "SAM3/4 DMA enabled but CONFIG_ARCH_DMA disabled"
#endif
/* Check the number of link list descriptors to allocate */

View File

@ -132,10 +132,12 @@ config SAMA5_ADC
config SAMA5_DMAC0
bool "DMA Controller 0 (DMAC0)"
default n
select ARCH_DMA
config SAMA5_DMAC1
bool "DMA Controller 1 (DMAC1)"
default n
select ARCH_DMA
config SAMA5_UHPHS
bool "USB Host High Speed (UHPHS)"

View File

@ -93,3 +93,13 @@ CHIP_CSRCS = sam_allocateheap.c sam_boot.c sam_clockconfig.c sam_gpio.c
CHIP_CSRCS += sam_irq.c sam_lowputc.c sam_serial.c sam_timerisr.c
# Configuration dependent C and assembly language files
ifeq ($(CONFIG_SAMA5_DMAC0),y)
CHIP_CSRCS += sam_dmac.c
else
ifeq ($(CONFIG_SAMA5_DMAC1),y)
CHIP_CSRCS += sam_dmac.c
else
endif
endif

View File

@ -88,8 +88,8 @@
#define SAM_DMAC_CH_SPIP_OFFSET 0x0018 /* DMAC Channel Source PinP Configuration Register */
#define SAM_DMAC_CH_DPIP_OFFSET 0x001c /* DMAC Channel Destination PinP Configuration Register */
/* 0x20-0x24: Reserved */
#define SAM_DMAC_CH_WPMR_OFFSET 0x01e4 /* DMAC Write Protect Mode Register */
#define SAM_DMAC_CH_WPSR_OFFSET 0x01e8 /* DMAC Write Protect Status Register */
#define SAM_DMAC_WPMR_OFFSET 0x01e4 /* DMAC Write Protect Mode Register */
#define SAM_DMAC_WPSR_OFFSET 0x01e8 /* DMAC Write Protect Status Register */
/* 0x01ec-0x1fc: Reserved */
/* DMAC0 register adresses **************************************************************/
@ -108,8 +108,8 @@
#define SAM_DMAC0_CHDR (SAM_DMAC0_VBASE+SAM_DMAC_CHDR_OFFSET)
#define SAM_DMAC0_CHSR (SAM_DMAC0_VBASE+SAM_DMAC_CHSR_OFFSET)
#define SAM_DMAC0_CH_WPMR (SAM_DMAC0_VBASE+SAM_DMAC_CH_WPMR_OFFSET)
#define SAM_DMAC0_CH_WPSR (SAM_DMAC0_VBASE+SAM_DMAC_CH_WPSR_OFFSET)
#define SAM_DMAC0_WPMR (SAM_DMAC0_VBASE+SAM_DMAC_WPMR_OFFSET)
#define SAM_DMAC0_WPSR (SAM_DMAC0_VBASE+SAM_DMAC_WPSR_OFFSET)
/* DMAC0 channel registers */
@ -220,8 +220,8 @@
#define SAM_DMAC1_CHDR (SAM_DMAC1_VBASE+SAM_DMAC_CHDR_OFFSET)
#define SAM_DMAC1_CHSR (SAM_DMAC1_VBASE+SAM_DMAC_CHSR_OFFSET)
#define SAM_DMAC1_CH_WPMR (SAM_DMAC1_VBASE+SAM_DMAC_CH_WPMR_OFFSET)
#define SAM_DMAC1_CH_WPSR (SAM_DMAC1_VBASE+SAM_DMAC_CH_WPSR_OFFSET)
#define SAM_DMAC1_WPMR (SAM_DMAC1_VBASE+SAM_DMAC_WPMR_OFFSET)
#define SAM_DMAC1_WPSR (SAM_DMAC1_VBASE+SAM_DMAC_WPSR_OFFSET)
/* DMAC1 channel registers */
@ -325,7 +325,7 @@
#define DMAC_GCFG_ARB_CFG (1 << 4) /* Bit 4: Arbiter Configuration */
# define DMAC_GCFG_ARB_FIXED (0) /* Bit 4=0: Fixed priority arbiter */
# define DMAC_GCFG_ARB_ROUNDROBIN (1 << 4) /* Bit 4=1: Round robin arbiter */
#define DMAC_DICEN (1 << 8) /* Bit 8: Descriptor Integrity Check
#define DMAC_DICEN (1 << 8) /* Bit 8: Descriptor Integrity Check */
/* DMAC Enable Register */
@ -683,6 +683,12 @@
#define DMAC_CH_CTRLB_DST_PIP (1 << 12) /* Bit 12: Destination Picture-in-Picture Mode */
#define DMAC_CH_CTRLB_SRCDSCR (1 << 16) /* Bit 16: Source buffer descriptor fetch operation disabled */
#define DMAC_CH_CTRLB_DSTDSCR (1 << 20) /* Bit 20: Dest buffer descriptor fetch operation disabled */
#define DMAC_CH_CTRLB_FC_SHIFT (21) /* Bits 21-22: Flow controller */
#define DMAC_CH_CTRLB_FC_MASK (3 << DMAC_CH_CTRLB_FC_SHIFT)
# define DMAC_CH_CTRLB_FC_M2M (0 << DMAC_CH_CTRLB_FC_SHIFT) /* Memory-to-Memory */
# define DMAC_CH_CTRLB_FC_M2P (1 << DMAC_CH_CTRLB_FC_SHIFT) /* Memory-to-Peripheral */
# define DMAC_CH_CTRLB_FC_P2M (2 << DMAC_CH_CTRLB_FC_SHIFT) /* Peripheral-to-Memory */
# define DMAC_CH_CTRLB_FC_P2P (3 << DMAC_CH_CTRLB_FC_SHIFT) /* Peripheral-to-Peripheral */
#define DMAC_CH_CTRLB_SRCINCR_SHIFT (24) /* Bits 24-25 */
#define DMAC_CH_CTRLB_SRCINCR_MASK (3 << DMAC_CH_CTRLB_SRCINCR_SHIFT)
# define DMAC_CH_CTRLB_SRCINCR_INCR (0 << DMAC_CH_CTRLB_SRCINCR_SHIFT) /* Incrementing address */
@ -752,6 +758,53 @@
#define DMAC_WPSR_WPVSRC_SHIFT (8) /* Bits 8-23: Write Protect Violation Source */
#define DMAC_WPSR_WPVSRC_MASK (0xffff << DMAC_WPSR_WPVSRC_SHIFT)
/* DMA Channel Definitions **************************************************************/
/* DMA Controller 0 Channel Definitions */
#define DMAC0_CH_HSMCI0 (0) /* HSMCI0 Receive/transmit */
#define DMAC0_CH_SPI0_TX (1) /* SPI0 Transmit */
#define DMAC0_CH_SPI0_RX (2) /* SPI0 Receive */
#define DMAC0_CH_USART0_TX (3) /* USART0 Transmit */
#define DMAC0_CH_USART0_RX (4) /* USART0 Receive */
#define DMAC0_CH_USART1_TX (5) /* USART1 Transmit */
#define DMAC0_CH_USART1_RX (6) /* USART1 Receive */
#define DMAC0_CH_TWI0_TX (7) /* TWI0 Transmit */
#define DMAC0_CH_TWI0_RX (8) /* TWI0 Receive */
#define DMAC0_CH_TWI1_TX (9) /* TWI1 Transmit */
#define DMAC0_CH_TWI1_RX (10) /* TWI1 Receive */
#define DMAC0_CH_UART0_TX (11) /* UART0 Transmit */
#define DMAC0_CH_UART0_RX (12) /* UART0 Receive */
#define DMAC0_CH_SSC0_TX (13) /* SSC0 Transmit */
#define DMAC0_CH_SSC0_RX (14) /* SSC0 Receive */
#define DMAC0_CH_SMD_TX (15) /* SMD Transmit */
#define DMAC0_CH_SMD_RX (16) /* SMD Receive */
/* DMA Controller 0 Channel Definitions */
#define DMAC1_CH_HSMCI1 (0) /* HSMCI1 Receive/transmit */
#define DMAC1_CH_HSMCI2 (1) /* HSMCI2 Receive/transmit */
#define DMAC1_CH_ADC_RX (2) /* ADC Receive */
#define DMAC1_CH_SSC1_TX (3) /* SSC1 Transmit */
#define DMAC1_CH_SSC1_RX (4) /* SSC1 Receive */
#define DMAC1_CH_UART1_TX (5) /* UART1 Transmit */
#define DMAC1_CH_UART1_RX (6) /* UART1 Receive */
#define DMAC1_CH_USART2_TX (7) /* USART2 Transmit */
#define DMAC1_CH_USART2_RX (8) /* USART2 Receive */
#define DMAC1_CH_USART3_TX (9) /* USART3 Transmit */
#define DMAC1_CH_USART3_RX (10) /* USART3 Receive */
#define DMAC1_CH_TWI2_TX (11) /* TWI2 Transmit */
#define DMAC1_CH_TWI2_RX (12) /* TWI2 Receive */
#define DMAC1_CH_DBGU_TX (13) /* DBGU Transmit */
#define DMAC1_CH_DBGU_RX (14) /* DBGU Receive */
#define DMAC1_CH_SPI1_TX (15) /* SPI1 Transmit */
#define DMAC1_CH_SPI1_RX (16) /* SPI1 Receive */
#define DMAC1_CH_SHA_TX (17) /* SHA Transmit */
#define DMAC1_CH_AES_TX (18) /* AES Transmit */
#define DMAC1_CH_AES_RX (19) /* AES Receive */
#define DMAC1_CH_TDES_TX (20) /* TDES Transmit */
#define DMAC1_CH_TDES_RX (21) /* TDES Receive */
/****************************************************************************************
* Public Types
****************************************************************************************/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,301 @@
/************************************************************************************
* arch/arm/src/sama5/sam_dmac.h
*
* Copyright (C) 2013 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_SAMA5_SAM_DMAC_H
#define __ARCH_ARM_SRC_SAMA5_SAM_DMAC_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include "chip.h"
/************************************************************************************
* Definitions
************************************************************************************/
/* Configuration ********************************************************************/
#ifndef CONFIG_DEBUG
# undef CONFIG_DEBUG_DMA
#endif
/* DMA ******************************************************************************/
/* Flags used to characterize the desired DMA channel. The naming convention is that
* one side is the peripheral and the other is memory (however, the interface could still
* be used if, for example, both sides were memory although the naming would be awkward)
*/
/* Select the DMA controller */
#define DMACH_FLAG_DMAC (1 << 0) /* 0=DMAC0, 1=DMAC1 */
# define DMACH_FLAG_DMAC0 (0) /* DMAC0 */
# define DMACH_FLAG_DMAC1 (1 << 0) /* DMAC1 */
/* Configurable properties of the channel */
#define DMACH_FLAG_BURST_LARGEST 0 /* Largest length AHB burst */
#define DMACH_FLAG_BURST_HALF 1 /* Half FIFO size */
#define DMACH_FLAG_BURST_SINGLE 2 /* Single AHB access */
#define DMACH_FLAG_FIFOCFG_SHIFT (1) /* Bits 1-2: FIFO configuration */
#define DMACH_FLAG_FIFOCFG_MASK (3 << DMACH_FLAG_FIFOCFG_SHIFT)
# define DMACH_FLAG_FIFOCFG_LARGEST (DMACH_FLAG_BURST_LARGEST << DMACH_FLAG_FIFOCFG_SHIFT)
# define DMACH_FLAG_FIFOCFG_HALF (DMACH_FLAG_BURST_HALF << DMACH_FLAG_FIFOCFG_SHIFT)
# define DMACH_FLAG_FIFOCFG_SINGLE (DMACH_FLAG_BURST_SINGLE << DMACH_FLAG_FIFOCFG_SHIFT)
/* Peripheral endpoint characteristics */
#define DMACH_FLAG_PERIPHPID_SHIFT (3) /* Bits 3-6: Peripheral PID */
#define DMACH_FLAG_PERIPHPID_MASK (15 << DMACH_FLAG_PERIPHPID_SHIFT)
#define DMACH_FLAG_PERIPHH2SEL (1 << 7) /* Bits 7: HW handshaking */
#define DMACH_FLAG_PERIPHISPERIPH (1 << 8) /* Bits 8: 0=memory; 1=peripheral */
#define DMACH_FLAG_PERIPHWIDTH_SHIFT (9) /* Bits 9-10: Peripheral width */
#define DMACH_FLAG_PERIPHWIDTH_MASK (3 << DMACH_FLAG_PERIPHWIDTH_SHIFT)
# define DMACH_FLAG_PERIPHWIDTH_8BITS (0 << DMACH_FLAG_PERIPHWIDTH_SHIFT) /* 8 bits */
# define DMACH_FLAG_PERIPHWIDTH_16BITS (1 << DMACH_FLAG_PERIPHWIDTH_SHIFT) /* 16 bits */
# define DMACH_FLAG_PERIPHWIDTH_32BITS (2 << DMACH_FLAG_PERIPHWIDTH_SHIFT) /* 32 bits */
# define DMACH_FLAG_PERIPHWIDTH_64BITS (3 << DMACH_FLAG_PERIPHWIDTH_SHIFT) /* 64 bits */
#define DMACH_FLAG_PERIPHINCREMENT (1 << 11) /* Bit 11: Autoincrement peripheral address */
#define DMACH_FLAG_PERIPHCHUNKSIZE (1 << 12) /* Bit 12: Peripheral chunk size */
# define DMACH_FLAG_PERIPHCHUNKSIZE_1 (0) /* Peripheral chunksize = 1 */
# define DMACH_FLAG_PERIPHCHUNKSIZE_4 DMACH_FLAG_PERIPHCHUNKSIZE /* Peripheral chunksize = 4 */
/* Memory endpoint characteristics */
#define DMACH_FLAG_MEMPID_SHIFT (13) /* Bits 13-14: Memory PID */
#define DMACH_FLAG_MEMPID_MASK (15 << DMACH_FLAG_PERIPHPID_SHIFT)
#define DMACH_FLAG_MEMH2SEL (1 << 15) /* Bits 15: HW handshaking */
#define DMACH_FLAG_MEMISPERIPH (1 << 16) /* Bits 16: 0=memory; 1=peripheral */
#define DMACH_FLAG_MEMWIDTH_SHIFT (17) /* Bits 17-18: Memory width */
#define DMACH_FLAG_MEMWIDTH_MASK (3 << DMACH_FLAG_MEMWIDTH_SHIFT)
# define DMACH_FLAG_MEMWIDTH_8BITS (0 << DMACH_FLAG_MEMWIDTH_SHIFT) /* 8 bits */
# define DMACH_FLAG_MEMWIDTH_16BITS (1 << DMACH_FLAG_MEMWIDTH_SHIFT) /* 16 bits */
# define DMACH_FLAG_MEMWIDTH_32BITS (2 << DMACH_FLAG_MEMWIDTH_SHIFT) /* 32 bits */
# define DMACH_FLAG_MEMWIDTH_64BITS (3 << DMACH_FLAG_MEMWIDTH_SHIFT) /* 64 bits */
#define DMACH_FLAG_MEMINCREMENT (1 << 19) /* Bit 19: Autoincrement memory address */
#define DMACH_FLAG_MEMCHUNKSIZE (1 << 20) /* Bit 20: Memory chunk size */
# define DMACH_FLAG_MEMCHUNKSIZE_1 (0) /* Memory chunksize = 1 */
# define DMACH_FLAG_MEMCHUNKSIZE_4 DMACH_FLAG_MEMCHUNKSIZE /* Memory chunksize = 4 */
/************************************************************************************
* Public Types
************************************************************************************/
typedef FAR void *DMA_HANDLE;
typedef void (*dma_callback_t)(DMA_HANDLE handle, void *arg, int result);
/* The following is used for sampling DMA registers when CONFIG DEBUG_DMA is selected */
#ifdef CONFIG_DEBUG_DMA
struct sam_dmaregs_s
{
/* Global Registers */
uint32_t gcfg; /* DMAC Global Configuration Register */
uint32_t en; /* DMAC Enable Register */
uint32_t sreq; /* DMAC Software Single Request Register */
uint32_t creq; /* DMAC Software Chunk Transfer Request Register */
uint32_t last; /* DMAC Software Last Transfer Flag Register */
uint32_t ebcimr; /* DMAC Error Mask */
uint32_t ebcisr; /* DMAC Error Status */
uint32_t chsr; /* DMAC Channel Handler Status Register */
uint32_t wpmr; /* DMAC Write Protect Mode Register */
uint32_t wpsr; /* DMAC Write Protect Status Register */
/* Channel Registers */
uint32_t saddr; /* DMAC Channel Source Address Register */
uint32_t daddr; /* DMAC Channel Destination Address Register */
uint32_t dscr; /* DMAC Channel Descriptor Address Register */
uint32_t ctrla; /* DMAC Channel Control A Register */
uint32_t ctrlb; /* DMAC Channel Control B Register */
uint32_t cfg; /* DMAC Channel Configuration Register */
uint32_t spip; /* DMAC Channel Source PinP Configuration Register */
uint32_t dpip; /* DMAC Channel Destination PinP Configuration Register */
};
#endif
/************************************************************************************
* Inline Functions
************************************************************************************/
#ifndef __ASSEMBLY__
/************************************************************************************
* Public Data
************************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
/****************************************************************************
* Name: sam_dmachannel
*
* Description:
* Allocate a DMA channel. This function sets aside a DMA channel with
* the required FIFO size and flow control capabilities (determined by
* dma_flags) then gives the caller exclusive access to the DMA channel.
*
* The naming convention in all of the DMA interfaces is that one side is
* the 'peripheral' and the other is 'memory'. Howerver, the interface
* could still be used if, for example, both sides were memory although
* the naming would be awkward.
*
* Returned Value:
* If a DMA channel if the required FIFO size is available, this function
* returns a non-NULL, void* DMA channel handle. NULL is returned on any
* failure.
*
****************************************************************************/
DMA_HANDLE sam_dmachannel(uint32_t dmach_flags);
/****************************************************************************
* Name: sam_dmafree
*
* Description:
* Release a DMA channel. NOTE: The 'handle' used in this argument must
* NEVER be used again until sam_dmachannel() is called again to re-gain
* a valid handle.
*
* Returned Value:
* None
*
****************************************************************************/
void sam_dmafree(DMA_HANDLE handle);
/****************************************************************************
* Name: sam_dmatxsetup
*
* Description:
* Configure DMA for transmit of one buffer (memory to peripheral). This
* function may be called multiple times to handle large and/or dis-
* continuous transfers. Calls to sam_dmatxsetup() and sam_dmarxsetup()
* must not be intermixed on the same transfer, however.
*
****************************************************************************/
int sam_dmatxsetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr,
size_t nbytes);
/****************************************************************************
* Name: sam_dmarxsetup
*
* Description:
* Configure DMA for receipt of one buffer (peripheral to memory). This
* function may be called multiple times to handle large and/or dis-
* continuous transfers. Calls to sam_dmatxsetup() and sam_dmarxsetup()
* must not be intermixed on the same transfer, however.
*
****************************************************************************/
int sam_dmarxsetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr,
size_t nbytes);
/****************************************************************************
* Name: sam_dmastart
*
* Description:
* Start the DMA transfer
*
****************************************************************************/
int sam_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg);
/****************************************************************************
* Name: sam_dmastop
*
* Description:
* Cancel the DMA. After sam_dmastop() is called, the DMA channel is
* reset and sam_dmarx/txsetup() must be called before sam_dmastart() can be
* called again
*
****************************************************************************/
void sam_dmastop(DMA_HANDLE handle);
/****************************************************************************
* Name: sam_dmasample
*
* Description:
* Sample DMA register contents
*
****************************************************************************/
#ifdef CONFIG_DEBUG_DMA
void sam_dmasample(DMA_HANDLE handle, struct sam_dmaregs_s *regs);
#else
# define sam_dmasample(handle,regs)
#endif
/****************************************************************************
* Name: sam_dmadump
*
* Description:
* Dump previously sampled DMA register contents
*
****************************************************************************/
#ifdef CONFIG_DEBUG_DMA
void sam_dmadump(DMA_HANDLE handle, const struct sam_dmaregs_s *regs,
const char *msg);
#else
# define sam_dmadump(handle,regs,msg)
#endif
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_SAMA5_SAM_DMAC_H */