From 0eda7244af71108683fb409517ccb18dd78dd65c Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 3 Oct 2011 23:58:25 +0000 Subject: SAM3U SPI driver update git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4017 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/sam3u/sam3u_internal.h | 32 +-- nuttx/arch/arm/src/sam3u/sam3u_spi.c | 293 ++++++++++++++++------- nuttx/arch/arm/src/sam3u/sam3u_spi.h | 377 +++++++++++++++--------------- 3 files changed, 411 insertions(+), 291 deletions(-) (limited to 'nuttx/arch') diff --git a/nuttx/arch/arm/src/sam3u/sam3u_internal.h b/nuttx/arch/arm/src/sam3u/sam3u_internal.h index d50d59635..ed125eaba 100644 --- a/nuttx/arch/arm/src/sam3u/sam3u_internal.h +++ b/nuttx/arch/arm/src/sam3u/sam3u_internal.h @@ -248,27 +248,15 @@ #define GPIO_SPI0_MISO (GPIO_PERIPHA|GPIO_CFG_DEFAULT|GPIO_PORT_PIOA|GPIO_PIN13) #define GPIO_SPI0_MOSI (GPIO_PERIPHA|GPIO_CFG_DEFAULT|GPIO_PORT_PIOA|GPIO_PIN14) #define GPIO_SPI0_SPCK (GPIO_PERIPHA|GPIO_CFG_DEFAULT|GPIO_PORT_PIOA|GPIO_PIN15) -#if 0 -# define GPIO_SPI0_NPCS0 (GPIO_PERIPHA|GPIO_CFG_DEFAULT|GPIO_PORT_PIOA|GPIO_PIN16) -# define GPIO_SPI0_NPCS1_1 (GPIO_PERIPHB|GPIO_CFG_DEFAULT|GPIO_PORT_PIOA|GPIO_PIN0) -# define GPIO_SPI0_NPCS1_2 (GPIO_PERIPHB|GPIO_CFG_DEFAULT|GPIO_PORT_PIOC|GPIO_PIN3) -# define GPIO_SPI0_NPCS1_3 (GPIO_PERIPHB|GPIO_CFG_DEFAULT|GPIO_PORT_PIOC|GPIO_PIN19) -# define GPIO_SPI0_NPCS2_1 (GPIO_PERIPHB|GPIO_CFG_DEFAULT|GPIO_PORT_PIOA|GPIO_PIN1) -# define GPIO_SPI0_NPCS2_2 (GPIO_PERIPHB|GPIO_CFG_DEFAULT|GPIO_PORT_PIOC|GPIO_PIN4) -# define GPIO_SPI0_NPCS2_3 (GPIO_PERIPHB|GPIO_CFG_DEFAULT|GPIO_PORT_PIOC|GPIO_PIN14) -# define GPIO_SPI0_NPCS3_1 (GPIO_PERIPHB|GPIO_CFG_DEFAULT|GPIO_PORT_PIOA|GPIO_PIN19) -# define GPIO_SPI0_NPCS3_2 (GPIO_PERIPHB|GPIO_CFG_DEFAULT|GPIO_PORT_PIOC|GPIO_PIN5) -#else -# define GPIO_SPI0_NPCS0 (GPIO_OUTPUT|GPIO_CFG_PULLUP|GPIO_OUTPUT_CLEAR|GPIO_PORT_PIOA|GPIO_PIN16) -# define GPIO_SPI0_NPCS1_1 (GPIO_OUTPUT|GPIO_CFG_PULLUP|GPIO_OUTPUT_CLEAR|GPIO_PORT_PIOA|GPIO_PIN0) -# define GPIO_SPI0_NPCS1_2 (GPIO_OUTPUT|GPIO_CFG_PULLUP|GPIO_OUTPUT_CLEAR|GPIO_PORT_PIOC|GPIO_PIN3) -# define GPIO_SPI0_NPCS1_3 (GPIO_OUTPUT|GPIO_CFG_PULLUP|GPIO_OUTPUT_CLEAR|GPIO_PORT_PIOC|GPIO_PIN19) -# define GPIO_SPI0_NPCS2_1 (GPIO_OUTPUT|GPIO_CFG_PULLUP|GPIO_OUTPUT_CLEAR|GPIO_PORT_PIOA|GPIO_PIN1) -# define GPIO_SPI0_NPCS2_2 (GPIO_OUTPUT|GPIO_CFG_PULLUP|GPIO_OUTPUT_CLEAR|GPIO_PORT_PIOC|GPIO_PIN4) -# define GPIO_SPI0_NPCS2_3 (GPIO_OUTPUT|GPIO_CFG_PULLUP|GPIO_OUTPUT_CLEAR|GPIO_PORT_PIOC|GPIO_PIN14) -# define GPIO_SPI0_NPCS3_1 (GPIO_OUTPUT|GPIO_CFG_PULLUP|GPIO_OUTPUT_CLEAR|GPIO_PORT_PIOA|GPIO_PIN19) -# define GPIO_SPI0_NPCS3_2 (GPIO_OUTPUT|GPIO_CFG_PULLUP|GPIO_OUTPUT_CLEAR|GPIO_PORT_PIOC|GPIO_PIN5) -#endif +#define GPIO_SPI0_NPCS0 (GPIO_PERIPHA|GPIO_CFG_DEFAULT|GPIO_PORT_PIOA|GPIO_PIN16) +#define GPIO_SPI0_NPCS1_1 (GPIO_PERIPHB|GPIO_CFG_DEFAULT|GPIO_PORT_PIOA|GPIO_PIN0) +#define GPIO_SPI0_NPCS1_2 (GPIO_PERIPHB|GPIO_CFG_DEFAULT|GPIO_PORT_PIOC|GPIO_PIN3) +#define GPIO_SPI0_NPCS1_3 (GPIO_PERIPHB|GPIO_CFG_DEFAULT|GPIO_PORT_PIOC|GPIO_PIN19) +#define GPIO_SPI0_NPCS2_1 (GPIO_PERIPHB|GPIO_CFG_DEFAULT|GPIO_PORT_PIOA|GPIO_PIN1) +#define GPIO_SPI0_NPCS2_2 (GPIO_PERIPHB|GPIO_CFG_DEFAULT|GPIO_PORT_PIOC|GPIO_PIN4) +#define GPIO_SPI0_NPCS2_3 (GPIO_PERIPHB|GPIO_CFG_DEFAULT|GPIO_PORT_PIOC|GPIO_PIN14) +#define GPIO_SPI0_NPCS3_1 (GPIO_PERIPHB|GPIO_CFG_DEFAULT|GPIO_PORT_PIOA|GPIO_PIN19) +#define GPIO_SPI0_NPCS3_2 (GPIO_PERIPHB|GPIO_CFG_DEFAULT|GPIO_PORT_PIOC|GPIO_PIN5) #define GPIO_SSC_TD (GPIO_PERIPHA|GPIO_CFG_DEFAULT|GPIO_PORT_PIOA|GPIO_PIN26) #define GPIO_SSC_TK (GPIO_PERIPHA|GPIO_CFG_DEFAULT|GPIO_PORT_PIOA|GPIO_PIN28) @@ -804,7 +792,7 @@ struct spi_dev_s; enum spi_dev_e; #ifdef CONFIG_SAM3U_SPI -EXTERN void sam3u_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); +EXTERN int sam3u_spiselect(enum spi_dev_e devid); EXTERN uint8_t sam3u_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid); #ifdef CONFIG_SPI_CMDDATA EXTERN int sam3u_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); diff --git a/nuttx/arch/arm/src/sam3u/sam3u_spi.c b/nuttx/arch/arm/src/sam3u/sam3u_spi.c index e3ba0a1bf..72f35ebe3 100644 --- a/nuttx/arch/arm/src/sam3u/sam3u_spi.c +++ b/nuttx/arch/arm/src/sam3u/sam3u_spi.c @@ -2,7 +2,8 @@ * arch/arm/src/sam3u/sam3u_spi.c * * Copyright (C) 2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Authors: Gregory Nutt + * Diego Sanchez * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -82,24 +83,32 @@ # define spivdbg(x...) #endif -/* SPI Clocking */ - -#warning "Missing logi" - /**************************************************************************** * Private Types ****************************************************************************/ -struct sam3u_spidev_s -{ - struct spi_dev_s spidev; /* Externally visible part of the SPI interface */ +/* The state of one chip select */ + #ifndef CONFIG_SPI_OWNBUS - sem_t exclsem; /* Held while chip is selected for mutual exclusion */ +struct sam3u_chipselect_s +{ uint32_t frequency; /* Requested clock frequency */ uint32_t actual; /* Actual clock frequency */ uint8_t nbits; /* Width of word in bits (8 to 16) */ uint8_t mode; /* Mode 0,1,2,3 */ +}; +#endif + +/* The overall state of the SPI interface */ + +struct sam3u_spidev_s +{ + struct spi_dev_s spidev; /* Externally visible part of the SPI interface */ +#ifndef CONFIG_SPI_OWNBUS + sem_t exclsem; /* Held while chip is selected for mutual exclusion */ + struct sam3u_chipselect_s csstate[4]; #endif + uint8_t cs; /* Chip select number */ }; /**************************************************************************** @@ -123,12 +132,14 @@ static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_ * Private Data ****************************************************************************/ +/* SPI driver operations */ + static const struct spi_ops_s g_spiops = { #ifndef CONFIG_SPI_OWNBUS .lock = spi_lock, #endif - .select = sam3u_spiselect, + .select = spi_select, .setfrequency = spi_setfrequency, .setmode = spi_setmode, .setbits = spi_setbits, @@ -142,11 +153,20 @@ static const struct spi_ops_s g_spiops = .registercallback = 0, /* Not implemented */ }; +/* SPI device structure */ + static struct sam3u_spidev_s g_spidev = { .spidev = { &g_spiops }, }; +/* This array maps chip select numbers (0-3) to CSR register addresses */ + +static const uint32_t g_csraddr[4] = +{ + SAM3U_SPI_CSR0, SAM3U_SPI_CSR1, SAM3U_SPI_CSR2, SAM3U_SPI_CSR3 +}; + /**************************************************************************** * Public Data ****************************************************************************/ @@ -202,6 +222,65 @@ static int spi_lock(FAR struct spi_dev_s *dev, bool lock) } #endif +/**************************************************************************** + * Name: spi_select + * + * Description: + * This function does not actually set the chip select line. Rather, it + * simply maps the device ID into a chip select number and retains that + * chip select number for later use. + * + * Input Parameters: + * dev - Device-specific state data + * frequency - The SPI frequency requested + * + * Returned Value: + * Returns the actual frequency selected + * + ****************************************************************************/ + + static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) + { + FAR struct sam3u_spidev_s *priv = (FAR struct sam3u_spidev_s *)dev; + uint32_t regval; + + /* Are we selecting or de-selecting the device? */ + + if (selected) + { + /* At this point, we expect no chip selected */ + + DEBUGASSERT(priv->cs == 0xff); + + /* Get the chip select associated with this SPI device */ + + priv->cs = sam3u_spiselect(devid); + DEBUGASSERT(priv->cs >= 0 && priv->cs <= 3); + + /* Before writing the TDR, the PCS field in the SPI_MR register must be set + * in order to select a slave. + */ + + regval = getreg32(SAM3U_SPI_MR); + regval &= ~SPI_MR_PCS_MASK; + regval |= (priv->cs << SPI_MR_PCS_SHIFT); + putreg32(regval, SAM3U_SPI_MR); + } + else + { + /* At this point, we expect the chip to have already been selected */ + +#ifdef CONFIG_DEBUG + int cs = sam3u_spiselect(devid); + DEBUGASSERT(priv->cs == cs); +#endif + + /* Mark no chip selected */ + + priv->cs = 0xff; + } + } + /**************************************************************************** * Name: spi_setfrequency * @@ -221,34 +300,56 @@ static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency) { FAR struct sam3u_spidev_s *priv = (FAR struct sam3u_spidev_s *)dev; uint32_t actual; + uint32_t divisor; + uint32_t regval; + uint32_t regaddr; + + DEBUGASSERT(priv->cs >= 0 && priv->cs <= 3); - /* Check if the requested frequence is the same as the frequency selection */ + /* Check if the requested frequency is the same as the frequency selection */ #ifndef CONFIG_SPI_OWNBUS - if (priv->frequency == frequency) + if (priv->csstate[priv->cs].frequency == frequency) { /* We are already at this frequency. Return the actual. */ - return priv->actual; + return priv->csstate[priv->cs].actual; } #endif - /* Configure SPI to a frequency as close as possible to the requested - * frequency. - */ - -#warning "Missing logic" + /* Configure SPI to a frequency as close as possible to the requested frequency. */ - /* Calculate the actual actual frequency that is used */ + /* frequency = SPI_CLOCK / divisor, or divisor = SPI_CLOCK / frequency */ -#warning "Missing logic" - actual = 0; + divisor = SAM3U_MCK_FREQUENCY / frequency; + + if (divisor < 8) + { + divisor = 8; + } + else if (divisor > 254) + { + divisor = 254; + } + + divisor = (divisor + 1) & ~1; + + /* Save the new divisor value */ + + regaddr = g_csraddr[priv->cs]; + regval = getreg32(regaddr); + regval &= ~SPI_CSR_SCBR_MASK; + putreg32(divisor << SPI_CSR_SCBR_SHIFT, regaddr); + + /* Calculate the new actual */ + + actual = SAM3U_MCK_FREQUENCY / divisor; /* Save the frequency setting */ #ifndef CONFIG_SPI_OWNBUS - priv->frequency = frequency; - priv->actual = actual; + priv->csstate[priv->cs].frequency = frequency; + priv->csstate[priv->cs].actual = actual; #endif spidbg("Frequency %d->%d\n", frequency, actual); @@ -274,28 +375,37 @@ static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode) { FAR struct sam3u_spidev_s *priv = (FAR struct sam3u_spidev_s *)dev; uint32_t regval; + uint32_t regaddr; + + DEBUGASSERT(priv->cs >= 0 && priv->cs <= 3); /* Has the mode changed? */ #ifndef CONFIG_SPI_OWNBUS - if (mode != priv->mode) + if (mode != priv->csstate[priv->cs].mode) { #endif /* Yes... Set the mode appropriately */ -#warning "Missing logic" + + regaddr = g_csraddr[priv->cs]; + regval = getreg32(regaddr); + regval &= ~(SPI_CSR_CPOL|SPI_CSR_NCPHA); switch (mode) { - case SPIDEV_MODE0: /* CPOL=0; CPHA=0 */ + case SPIDEV_MODE0: /* CPOL=0; NCPHA=0 */ break; - case SPIDEV_MODE1: /* CPOL=0; CPHA=1 */ + case SPIDEV_MODE1: /* CPOL=0; NCPHA=1 */ + regval |= SPI_CSR_NCPHA; break; - case SPIDEV_MODE2: /* CPOL=1; CPHA=0 */ + case SPIDEV_MODE2: /* CPOL=1; NCPHA=0 */ + regval |= SPI_CSR_CPOL; break; - case SPIDEV_MODE3: /* CPOL=1; CPHA=1 */ + case SPIDEV_MODE3: /* CPOL=1; NCPHA=1 */ + regval |= (SPI_CSR_CPOL|SPI_CSR_NCPHA); break; default: @@ -303,10 +413,12 @@ static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode) return; } + putreg32(regval, regaddr); + /* Save the mode so that subsequent re-configurations will be faster */ #ifndef CONFIG_SPI_OWNBUS - priv->mode = mode; + priv->csstate[priv->cs].mode = mode; } #endif } @@ -329,22 +441,30 @@ static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode) static void spi_setbits(FAR struct spi_dev_s *dev, int nbits) { FAR struct sam3u_spidev_s *priv = (FAR struct sam3u_spidev_s *)dev; + uint32_t regaddr; uint32_t regval; /* Has the number of bits changed? */ DEBUGASSERT(priv && nbits > 7 && nbits < 17); + DEBUGASSERT(priv->cs >= 0 && priv->cs <= 3); + #ifndef CONFIG_SPI_OWNBUS - if (nbits != priv->nbits) + if (nbits != priv->csstate[priv->cs].nbits) { #endif /* Yes... Set number of bits appropriately */ -#warning "Missing logic" + + regaddr = g_csraddr[priv->cs]; + regval = getreg32(regaddr); + regval &= ~SPI_CSR_BITS_MASK; + regval |= SPI_CSR_BITS(nbits); + putreg32(regval, regaddr); /* Save the selection so the subsequence re-configurations will be faster */ #ifndef CONFIG_SPI_OWNBUS - priv->nbits = nbits; + priv->csstate[priv->cs].nbits = nbits; } #endif } @@ -367,15 +487,23 @@ static void spi_setbits(FAR struct spi_dev_s *dev, int nbits) static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t wd) { - /* Write the data to transmitted to the SPI Data Register */ -#warning "Missing logic" + /* Wait for any previous data written to the TDR to be transferred to the + * serializer. + */ - /* Wait for the data exchange to complete */ -#warning "Missing logic" + while ((getreg32(SAM3U_SPI_SR) & SPI_INT_TDRE) == 0); - /* Clear any pending status and return the received data */ -#warning "Missing logic" - return 0; + /* Write the data to transmitted to the Transmit Data Register (TDR) */ + + putreg32((uint32_t)wd, SAM3U_SPI_TDR); + + /* Wait for the read data to be available in the RDR */ + + while ((getreg32(SAM3U_SPI_SR) & SPI_INT_RDRF) == 0); + + /* Return the received data */ + + return (uint16_t)getreg32(SAM3U_SPI_RDR); } /************************************************************************* @@ -403,19 +531,21 @@ static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size uint8_t data; spidbg("nwords: %d\n", nwords); - while (nwords) - { - /* Write the data to transmitted to the SPI Data Register */ - data = *ptr++; -#warning "Missing logic" + /* Loop, sending each word in the user-provied data buffer */ - /* Wait for the data exchange to complete */ -#warning "Missing logic" + for ( ; nwords > 0; nwords--) + { + /* Wait for any previous data written to the TDR to be transferred + * to the serializer. + */ + + while ((getreg32(SAM3U_SPI_SR) & SPI_INT_TDRE) == 0); + + /* Write the data to transmitted to the Transmit Data Register (TDR) */ - /* Clear any pending status */ -#warning "Missing logic" - nwords--; + data = *ptr++; + putreg32((uint32_t)data, SAM3U_SPI_TDR); } } @@ -443,28 +573,30 @@ static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t nw FAR uint8_t *ptr = (FAR uint8_t*)buffer; spidbg("nwords: %d\n", nwords); - while (nwords) + + /* Loop, receiving each word */ + + for ( ; nwords > 0; nwords--) { - /* Write some dummy data to the SPI Data Register in order to clock the - * read data. + /* Wait for any previous data written to the TDR to be transferred + * to the serializer. + */ + + while ((getreg32(SAM3U_SPI_SR) & SPI_INT_TDRE) == 0); + + /* Write the some dummy data the Transmit Data Register (TDR) in order + * to clock the read data. */ -#warning "Missing logic" - - /* Wait for the data exchange to complete */ -#warning "Missing logic" + putreg32(0xff, SAM3U_SPI_TDR); - /* Read the received data from the SPI Data Register */ -#warning "Missing logic" + /* Wait for the read data to be available in the RDR */ - /* Clear any pending status */ -#warning "Missing logic" + while ((getreg32(SAM3U_SPI_SR) & SPI_INT_RDRF) == 0); - /* Read the received data from the SPI Data Register */ + /* Read the received data from the SPI Data Register */ -#warning "Missing logic" - *ptr++ = 0; - nwords--; + *ptr++ = (uint8_t)getreg32(SAM3U_SPI_RDR); } } @@ -496,6 +628,10 @@ FAR struct spi_dev_s *up_spiinitialize(int port) DEBUGASSERT(port == 0); + /* Set up the initial state */ + + priv->cs = 0xff; + /* Apply power to the SPI block */ flags = irqsave(); @@ -514,30 +650,25 @@ FAR struct spi_dev_s *up_spiinitialize(int port) sam3u_configgpio(GPIO_SPI0_MOSI); sam3u_configgpio(GPIO_SPI0_SPCK); - /* Execute a software reset of the SPI twice */ + /* Execute a software reset of the SPI (twice) */ putreg32(SPI_CR_SWRST, SAM3U_SPI_CR); putreg32(SPI_CR_SWRST, SAM3U_SPI_CR); - - /* Configure clocking */ -#warning "Missing logic - Check SPI MR register" - irqrestore(flags); - - /* Configure 8-bit SPI mode and master mode */ -#warning "Missing logic" - /* Set the initial SPI configuration */ + /* Configure the SPI mode register */ +#warning "Need to review this -- what other settngs are necessary" + putreg32(SPI_MR_MSTR, SAM3U_SPI_MR); -#ifndef CONFIG_SPI_OWNBUS - priv->frequency = 0; - priv->nbits = 8; - priv->mode = SPIDEV_MODE0; -#endif + /* And enable the SPI */ + + putreg32(SPI_CR_SPIEN, SAM3U_SPI_CR); + up_mdelay(20); - /* Select a default frequency of approx. 400KHz */ + /* Flush any pending transfers */ - spi_setfrequency((FAR struct spi_dev_s *)priv, 400000); + (void)getreg32(SAM3U_SPI_SR); + (void)getreg32(SAM3U_SPI_RDR); /* Initialize the SPI semaphore that enforces mutually exclusive access */ diff --git a/nuttx/arch/arm/src/sam3u/sam3u_spi.h b/nuttx/arch/arm/src/sam3u/sam3u_spi.h index f0d3af496..bce613575 100644 --- a/nuttx/arch/arm/src/sam3u/sam3u_spi.h +++ b/nuttx/arch/arm/src/sam3u/sam3u_spi.h @@ -1,188 +1,189 @@ -/**************************************************************************************** - * arch/arm/src/sam3u/sam3u_spi.h - * - * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_SAM3U_SAM3U_SPI_H -#define __ARCH_ARM_SRC_SAM3U_SAM3U_SPI_H - -/**************************************************************************************** - * Included Files - ****************************************************************************************/ - -#include - -#include "chip.h" -#include "sam3u_memorymap.h" - -/**************************************************************************************** - * Pre-processor Definitions - ****************************************************************************************/ - -/* SPI register offsets *****************************************************************/ - -#define SAM3U_SPI_CR_OFFSET 0x00 /* Control Register */ -#define SAM3U_SPI_MR_OFFSET 0x04 /* Mode Register */ -#define SAM3U_SPI_RDR_OFFSET 0x08 /* Receive Data Register */ -#define SAM3U_SPI_TDR_OFFSET 0x0c /* Transmit Data Register */ -#define SAM3U_SPI_SR_OFFSET 0x10 /* Status Register */ -#define SAM3U_SPI_IER_OFFSET 0x14 /* Interrupt Enable Register */ -#define SAM3U_SPI_IDR_OFFSET 0x18 /* Interrupt Disable Register */ -#define SAM3U_SPI_IMR_OFFSET 0x1c /* Interrupt Mask Register */ - /* 0x20-0x2c: Reserved */ -#define SAM3U_SPI_CSR0_OFFSET 0x30 /* Chip Select Register 0 */ -#define SAM3U_SPI_CSR1_OFFSET 0x34 /* Chip Select Register 1 */ -#define SAM3U_SPI_CSR2_OFFSET 0x38 /* Chip Select Register 2 */ -#define SAM3U_SPI_CSR3_OFFSET 0x3c /* Chip Select Register 3 */ - /* 0x40-0xe0: Reserved */ -#define SAM3U_SPI_WPCR_OFFSET 0xe4 /* Write Protection Control Register */ -#define SAM3U_SPI_WPSR_OFFSET 0xe8 /* Write Protection Status Register */ - /* 0xec-0xf8: Reserved*/ - -/* SPI register adresses ****************************************************************/ - -#define SAM3U_SPI_CR (SAM3U_SPI_BASE+SAM3U_SPI_CR_OFFSET) /* Control Register */ -#define SAM3U_SPI_MR (SAM3U_SPI_BASE+SAM3U_SPI_MR_OFFSET) /* Mode Register */ -#define SAM3U_SPI_RDR (SAM3U_SPI_BASE+SAM3U_SPI_RDR_OFFSET) /* Receive Data Register */ -#define SAM3U_SPI_TDR (SAM3U_SPI_BASE+SAM3U_SPI_TDR_OFFSET) /* Transmit Data Register */ -#define SAM3U_SPI_SR (SAM3U_SPI_BASE+SAM3U_SPI_SR_OFFSET) /* Status Register */ -#define SAM3U_SPI_IER (SAM3U_SPI_BASE+SAM3U_SPI_IER_OFFSET) /* Interrupt Enable Register */ -#define SAM3U_SPI_IDR (SAM3U_SPI_BASE+SAM3U_SPI_IDR_OFFSET) /* Interrupt Disable Register */ -#define SAM3U_SPI_IMR (SAM3U_SPI_BASE+SAM3U_SPI_IMR_OFFSET) /* Interrupt Mask Register */ -#define SAM3U_SPI_CSR0 (SAM3U_SPI_BASE+SAM3U_SPI_CSR0_OFFSET) /* Chip Select Register 0 */ -#define SAM3U_SPI_CSR1 (SAM3U_SPI_BASE+SAM3U_SPI_CSR1_OFFSET) /* Chip Select Register 1 */ -#define SAM3U_SPI_CSR2 (SAM3U_SPI_BASE+SAM3U_SPI_CSR2_OFFSET) /* Chip Select Register 2 */ -#define SAM3U_SPI_CSR3 (SAM3U_SPI_BASE+SAM3U_SPI_CSR3_OFFSET) /* Chip Select Register 3 */ -#define SAM3U_SPI_WPCR (SAM3U_SPI_BASE+SAM3U_SPI_WPCR_OFFSET) /* Write Protection Control Register */ -#define SAM3U_SPI_WPSR (SAM3U_SPI_BASE+SAM3U_SPI_WPSR_OFFSET) /* Write Protection Status Register */ - -/* SPI register bit definitions *********************************************************/ - -/* SPI Control Register */ - -#define SPI_CR_SPIEN (1 << 0) /* Bit 0: SPI Enable */ -#define SPI_CR_SPIDIS (1 << 1) /* Bit 1: SPI Disable */ -#define SPI_CR_SWRST (1 << 7) /* Bit 7: SPI Software Reset */ -#define SPI_CR_LASTXFER (1 << 24) /* Bit 24: Last Transfer */ - -/* SPI Mode Register */ - -#define SPI_MR_MSTR (1 << 0) /* Bit 0: Master/Slave Mode */ -#define SPI_MR_PS (1 << 1) /* Bit 1: Peripheral Select */ -#define SPI_MR_PCSDEC (1 << 2) /* Bit 2: Chip Select Decode */ -#define SPI_MR_MODFDIS (1 << 4) /* Bit 4: Mode Fault Detection */ -#define SPI_MR_WDRBT (1 << 5) /* Bit 5: Wait Data Read Before Transfer */ -#define SPI_MR_LLB (1 << 7) /* Bit 7: Local Loopback Enable */ -#define SPI_MR_PCS_SHIFT (16) /* Bits 16-19: Peripheral Chip Select */ -#define SPI_MR_PCS_MASK (15 << SPI_MR_PCS_SHIFT) -#define SPI_MR_DLYBCS_SHIFT (24) /* Bits 24-31: Delay Between Chip Selects */ -#define SPI_MR_DLYBCS_MASK (0xff << SPI_MR_DLYBCS_SHIFT) - -/* SPI Receive Data Register */ - -#define SPI_RDR_RD_SHIFT (0) /* Bits 0-15: Receive Data */ -#define SPI_RDR_RD_MASK (0xffff << SPI_RDR_RD_SHIFT) -#define SPI_RDR_PCS_SHIFT (16) /* Bits 16-19: Peripheral Chip Select */ -#define SPI_RDR_PCS_MASK (15 << SPI_RDR_PCS_SHIFT) - -/* SPI Transmit Data Register */ - -#define SPI_TDR_TD_SHIFT (0) /* Bits 0-15: Transmit Data */ -#define SPI_TDR_TD_MASK (0xffff << SPI_TDR_TD_SHIFT) -#define SPI_TDR_PCS_SHIFT (16) /* Bits 16-19: Peripheral Chip Select */ -#define SPI_TDR_PCS_MASK (15 << SPI_TDR_PCS_SHIFT) -#define SPI_TDR_LASTXFER (1 << 24) /* Bit 24: Last Transfer */ - -/* SPI Status Register, SPI Interrupt Enable Register, SPI Interrupt Disable Register, - * and SPI Interrupt Mask Register (common bit fields) - */ - -#define SPI_INT_RDRF (1 << 0) /* Bit 0: Receive Data Register Full Interrupt */ -#define SPI_INT_TDRE (1 << 1) /* Bit 1: Transmit Data Register Empty Interrupt */ -#define SPI_INT_MODF (1 << 2) /* Bit 2: Mode Fault Error Interrupt */ -#define SPI_INT_OVRES (1 << 3) /* Bit 3: Overrun Error Interrupt */ -#define SPI_INT_NSSR (1 << 8) /* Bit 8: NSS Rising Interrupt */ -#define SPI_INT_TXEMPTY (1 << 9) /* Bit 9: Transmission Registers Empty Interrupt */ -#define SPI_INT_UNDES (1 << 10) /* Bit 10: Underrun Error Status Interrupt (slave) */ -#define SPI_SR_SPIENS (1 << 16) /* Bit 16: SPI Enable Status (SR only) */ - -/* SPI Chip Select Registers 0-3 */ - -#define SPI_CSR_CPOL (1 << 0) /* Bit 0: Clock Polarity */ -#define SPI_CSR_NCPHA (1 << 1) /* Bit 1: Clock Phase */ -#define SPI_CSR_CSNAAT (1 << 2) /* Bit 2: Chip Select Not Active After Transfer */ -#define SPI_CSR_CSAAT (1 << 3) /* Bit 3: Chip Select Active After Transfer */ -#define SPI_CSR_BITS_SHIFT (4) /* Bits 4-7: Bits Per Transfer */ -#define SPI_CSR_BITS_MASK (15 << SPI_CSR_BITS_SHIFT) -# define SPI_CSR_BITS8 (0 << SPI_CSR_BITS_SHIFT) /* 8 */ -# define SPI_CSR_BITS9 (1 << SPI_CSR_BITS_SHIFT) /* 9 */ -# define SPI_CSR_BITS10 (2 << SPI_CSR_BITS_SHIFT) /* 10 */ -# define SPI_CSR_BITS11 (3 << SPI_CSR_BITS_SHIFT) /* 11 */ -# define SPI_CSR_BITS12 (4 << SPI_CSR_BITS_SHIFT) /* 12 */ -# define SPI_CSR_BITS13 (5 << SPI_CSR_BITS_SHIFT) /* 13 */ -# define SPI_CSR_BITS14 (6 << SPI_CSR_BITS_SHIFT) /* 14 */ -# define SPI_CSR_BITS15 (7 << SPI_CSR_BITS_SHIFT) /* 15 */ -# define SPI_CSR_BITS15 (8 << SPI_CSR_BITS_SHIFT) /* 16 */ -#define SPI_CSR_SCBR_SHIFT (8) /* Bits 8-15: Serial Clock Baud Rate */ -#define SPI_CSR_SCBR_MASK (0xff << SPI_CSR_SCBR_SHIFT) -#define SPI_CSR_DLYBS_SHIFT (16) /* Bits 16-23: Delay Before SPCK */ -#define SPI_CSR_DLYBS_MASK (0xff << SPI_CSR_DLYBS_SHIFT) -#define SPI_CSR_DLYBCT_SHIFT (24) /* Bits 24-31: Delay Between Consecutive Transfers */ -#define SPI_CSR_DLYBCT_MASK (0xff << SPI_CSR_DLYBCT_SHIFT) - -/* SPI Write Protection Control Register */ - -#define SPI_WPCR_SPIWPEN (1 << 0) /* Bit 0: SPI Write Protection Enable */ -#define SPI_WPCR_SPIWPKEY_SHIFT (8) /* Bits 8-31: SPI Write Protection Key Password */ -#define SPI_WPCR_SPIWPKEY_MASK (0x00ffffff << SPI_WPCR_SPIWPKEY_SHIFT) - -/* SPI Write Protection Status Register */ - -#define SPI_WPSR_SPIWPVS_SHIFT (0) /* Bits 0-2: SPI Write Protection Violation Status */ -#define SPI_WPSR_SPIWPVS_MASK (7 << SPI_WPSR_SPIWPVS_SHIFT) -#define SPI_WPSR_SPIWPVSRC_SHIFT (8) /* Bits 8-15: SPI Write Protection Violation Source */ -#define SPI_WPSR_SPIWPVSRC_MASK (0xff << SPI_WPSR_SPIWPVSRC_SHIFT) - -/**************************************************************************************** - * Public Types - ****************************************************************************************/ - -/**************************************************************************************** - * Public Data - ****************************************************************************************/ - -/**************************************************************************************** - * Public Functions - ****************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_SAM3U_SAM3U_SPI_H */ +/**************************************************************************************** + * arch/arm/src/sam3u/sam3u_spi.h + * + * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_SAM3U_SAM3U_SPI_H +#define __ARCH_ARM_SRC_SAM3U_SAM3U_SPI_H + +/**************************************************************************************** + * Included Files + ****************************************************************************************/ + +#include + +#include "chip.h" +#include "sam3u_memorymap.h" + +/**************************************************************************************** + * Pre-processor Definitions + ****************************************************************************************/ + +/* SPI register offsets *****************************************************************/ + +#define SAM3U_SPI_CR_OFFSET 0x00 /* Control Register */ +#define SAM3U_SPI_MR_OFFSET 0x04 /* Mode Register */ +#define SAM3U_SPI_RDR_OFFSET 0x08 /* Receive Data Register */ +#define SAM3U_SPI_TDR_OFFSET 0x0c /* Transmit Data Register */ +#define SAM3U_SPI_SR_OFFSET 0x10 /* Status Register */ +#define SAM3U_SPI_IER_OFFSET 0x14 /* Interrupt Enable Register */ +#define SAM3U_SPI_IDR_OFFSET 0x18 /* Interrupt Disable Register */ +#define SAM3U_SPI_IMR_OFFSET 0x1c /* Interrupt Mask Register */ + /* 0x20-0x2c: Reserved */ +#define SAM3U_SPI_CSR0_OFFSET 0x30 /* Chip Select Register 0 */ +#define SAM3U_SPI_CSR1_OFFSET 0x34 /* Chip Select Register 1 */ +#define SAM3U_SPI_CSR2_OFFSET 0x38 /* Chip Select Register 2 */ +#define SAM3U_SPI_CSR3_OFFSET 0x3c /* Chip Select Register 3 */ + /* 0x40-0xe0: Reserved */ +#define SAM3U_SPI_WPCR_OFFSET 0xe4 /* Write Protection Control Register */ +#define SAM3U_SPI_WPSR_OFFSET 0xe8 /* Write Protection Status Register */ + /* 0xec-0xf8: Reserved*/ + +/* SPI register adresses ****************************************************************/ + +#define SAM3U_SPI_CR (SAM3U_SPI_BASE+SAM3U_SPI_CR_OFFSET) /* Control Register */ +#define SAM3U_SPI_MR (SAM3U_SPI_BASE+SAM3U_SPI_MR_OFFSET) /* Mode Register */ +#define SAM3U_SPI_RDR (SAM3U_SPI_BASE+SAM3U_SPI_RDR_OFFSET) /* Receive Data Register */ +#define SAM3U_SPI_TDR (SAM3U_SPI_BASE+SAM3U_SPI_TDR_OFFSET) /* Transmit Data Register */ +#define SAM3U_SPI_SR (SAM3U_SPI_BASE+SAM3U_SPI_SR_OFFSET) /* Status Register */ +#define SAM3U_SPI_IER (SAM3U_SPI_BASE+SAM3U_SPI_IER_OFFSET) /* Interrupt Enable Register */ +#define SAM3U_SPI_IDR (SAM3U_SPI_BASE+SAM3U_SPI_IDR_OFFSET) /* Interrupt Disable Register */ +#define SAM3U_SPI_IMR (SAM3U_SPI_BASE+SAM3U_SPI_IMR_OFFSET) /* Interrupt Mask Register */ +#define SAM3U_SPI_CSR0 (SAM3U_SPI_BASE+SAM3U_SPI_CSR0_OFFSET) /* Chip Select Register 0 */ +#define SAM3U_SPI_CSR1 (SAM3U_SPI_BASE+SAM3U_SPI_CSR1_OFFSET) /* Chip Select Register 1 */ +#define SAM3U_SPI_CSR2 (SAM3U_SPI_BASE+SAM3U_SPI_CSR2_OFFSET) /* Chip Select Register 2 */ +#define SAM3U_SPI_CSR3 (SAM3U_SPI_BASE+SAM3U_SPI_CSR3_OFFSET) /* Chip Select Register 3 */ +#define SAM3U_SPI_WPCR (SAM3U_SPI_BASE+SAM3U_SPI_WPCR_OFFSET) /* Write Protection Control Register */ +#define SAM3U_SPI_WPSR (SAM3U_SPI_BASE+SAM3U_SPI_WPSR_OFFSET) /* Write Protection Status Register */ + +/* SPI register bit definitions *********************************************************/ + +/* SPI Control Register */ + +#define SPI_CR_SPIEN (1 << 0) /* Bit 0: SPI Enable */ +#define SPI_CR_SPIDIS (1 << 1) /* Bit 1: SPI Disable */ +#define SPI_CR_SWRST (1 << 7) /* Bit 7: SPI Software Reset */ +#define SPI_CR_LASTXFER (1 << 24) /* Bit 24: Last Transfer */ + +/* SPI Mode Register */ + +#define SPI_MR_MSTR (1 << 0) /* Bit 0: Master/Slave Mode */ +#define SPI_MR_PS (1 << 1) /* Bit 1: Peripheral Select */ +#define SPI_MR_PCSDEC (1 << 2) /* Bit 2: Chip Select Decode */ +#define SPI_MR_MODFDIS (1 << 4) /* Bit 4: Mode Fault Detection */ +#define SPI_MR_WDRBT (1 << 5) /* Bit 5: Wait Data Read Before Transfer */ +#define SPI_MR_LLB (1 << 7) /* Bit 7: Local Loopback Enable */ +#define SPI_MR_PCS_SHIFT (16) /* Bits 16-19: Peripheral Chip Select */ +#define SPI_MR_PCS_MASK (15 << SPI_MR_PCS_SHIFT) +#define SPI_MR_DLYBCS_SHIFT (24) /* Bits 24-31: Delay Between Chip Selects */ +#define SPI_MR_DLYBCS_MASK (0xff << SPI_MR_DLYBCS_SHIFT) + +/* SPI Receive Data Register */ + +#define SPI_RDR_RD_SHIFT (0) /* Bits 0-15: Receive Data */ +#define SPI_RDR_RD_MASK (0xffff << SPI_RDR_RD_SHIFT) +#define SPI_RDR_PCS_SHIFT (16) /* Bits 16-19: Peripheral Chip Select */ +#define SPI_RDR_PCS_MASK (15 << SPI_RDR_PCS_SHIFT) + +/* SPI Transmit Data Register */ + +#define SPI_TDR_TD_SHIFT (0) /* Bits 0-15: Transmit Data */ +#define SPI_TDR_TD_MASK (0xffff << SPI_TDR_TD_SHIFT) +#define SPI_TDR_PCS_SHIFT (16) /* Bits 16-19: Peripheral Chip Select */ +#define SPI_TDR_PCS_MASK (15 << SPI_TDR_PCS_SHIFT) +#define SPI_TDR_LASTXFER (1 << 24) /* Bit 24: Last Transfer */ + +/* SPI Status Register, SPI Interrupt Enable Register, SPI Interrupt Disable Register, + * and SPI Interrupt Mask Register (common bit fields) + */ + +#define SPI_INT_RDRF (1 << 0) /* Bit 0: Receive Data Register Full Interrupt */ +#define SPI_INT_TDRE (1 << 1) /* Bit 1: Transmit Data Register Empty Interrupt */ +#define SPI_INT_MODF (1 << 2) /* Bit 2: Mode Fault Error Interrupt */ +#define SPI_INT_OVRES (1 << 3) /* Bit 3: Overrun Error Interrupt */ +#define SPI_INT_NSSR (1 << 8) /* Bit 8: NSS Rising Interrupt */ +#define SPI_INT_TXEMPTY (1 << 9) /* Bit 9: Transmission Registers Empty Interrupt */ +#define SPI_INT_UNDES (1 << 10) /* Bit 10: Underrun Error Status Interrupt (slave) */ +#define SPI_SR_SPIENS (1 << 16) /* Bit 16: SPI Enable Status (SR only) */ + +/* SPI Chip Select Registers 0-3 */ + +#define SPI_CSR_CPOL (1 << 0) /* Bit 0: Clock Polarity */ +#define SPI_CSR_NCPHA (1 << 1) /* Bit 1: Clock Phase */ +#define SPI_CSR_CSNAAT (1 << 2) /* Bit 2: Chip Select Not Active After Transfer */ +#define SPI_CSR_CSAAT (1 << 3) /* Bit 3: Chip Select Active After Transfer */ +#define SPI_CSR_BITS_SHIFT (4) /* Bits 4-7: Bits Per Transfer */ +#define SPI_CSR_BITS_MASK (15 << SPI_CSR_BITS_SHIFT) +# define SPI_CSR_BITS(n) (((n)-8) << SPI_CSR_BITS_SHIFT) /* n, n=8-16 */ +# define SPI_CSR_BITS8 (0 << SPI_CSR_BITS_SHIFT) /* 8 */ +# define SPI_CSR_BITS9 (1 << SPI_CSR_BITS_SHIFT) /* 9 */ +# define SPI_CSR_BITS10 (2 << SPI_CSR_BITS_SHIFT) /* 10 */ +# define SPI_CSR_BITS11 (3 << SPI_CSR_BITS_SHIFT) /* 11 */ +# define SPI_CSR_BITS12 (4 << SPI_CSR_BITS_SHIFT) /* 12 */ +# define SPI_CSR_BITS13 (5 << SPI_CSR_BITS_SHIFT) /* 13 */ +# define SPI_CSR_BITS14 (6 << SPI_CSR_BITS_SHIFT) /* 14 */ +# define SPI_CSR_BITS15 (7 << SPI_CSR_BITS_SHIFT) /* 15 */ +# define SPI_CSR_BITS16 (8 << SPI_CSR_BITS_SHIFT) /* 16 */ +#define SPI_CSR_SCBR_SHIFT (8) /* Bits 8-15: Serial Clock Baud Rate */ +#define SPI_CSR_SCBR_MASK (0xff << SPI_CSR_SCBR_SHIFT) +#define SPI_CSR_DLYBS_SHIFT (16) /* Bits 16-23: Delay Before SPCK */ +#define SPI_CSR_DLYBS_MASK (0xff << SPI_CSR_DLYBS_SHIFT) +#define SPI_CSR_DLYBCT_SHIFT (24) /* Bits 24-31: Delay Between Consecutive Transfers */ +#define SPI_CSR_DLYBCT_MASK (0xff << SPI_CSR_DLYBCT_SHIFT) + +/* SPI Write Protection Control Register */ + +#define SPI_WPCR_SPIWPEN (1 << 0) /* Bit 0: SPI Write Protection Enable */ +#define SPI_WPCR_SPIWPKEY_SHIFT (8) /* Bits 8-31: SPI Write Protection Key Password */ +#define SPI_WPCR_SPIWPKEY_MASK (0x00ffffff << SPI_WPCR_SPIWPKEY_SHIFT) + +/* SPI Write Protection Status Register */ + +#define SPI_WPSR_SPIWPVS_SHIFT (0) /* Bits 0-2: SPI Write Protection Violation Status */ +#define SPI_WPSR_SPIWPVS_MASK (7 << SPI_WPSR_SPIWPVS_SHIFT) +#define SPI_WPSR_SPIWPVSRC_SHIFT (8) /* Bits 8-15: SPI Write Protection Violation Source */ +#define SPI_WPSR_SPIWPVSRC_MASK (0xff << SPI_WPSR_SPIWPVSRC_SHIFT) + +/**************************************************************************************** + * Public Types + ****************************************************************************************/ + +/**************************************************************************************** + * Public Data + ****************************************************************************************/ + +/**************************************************************************************** + * Public Functions + ****************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_SAM3U_SAM3U_SPI_H */ -- cgit v1.2.3