From 4b10c9b35c3f713d8db45008a9b3c0d31f222522 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 7 Nov 2013 12:26:53 -0600 Subject: SAMA5 SSC: Add framework (only) for a forthcoming SSC-based I2S driver --- nuttx/ChangeLog | 4 + nuttx/Kconfig | 9 + nuttx/arch/arm/src/sama5/Kconfig | 234 +++++++ nuttx/arch/arm/src/sama5/Make.defs | 9 + nuttx/arch/arm/src/sama5/chip/sam_ssc.h | 8 +- nuttx/arch/arm/src/sama5/sam_ssc.c | 1052 +++++++++++++++++++++++++++++++ nuttx/arch/arm/src/sama5/sam_ssc.h | 102 +++ nuttx/drivers/Kconfig | 26 +- nuttx/include/nuttx/audio/i2s.h | 44 +- 9 files changed, 1449 insertions(+), 39 deletions(-) create mode 100644 nuttx/arch/arm/src/sama5/sam_ssc.c create mode 100644 nuttx/arch/arm/src/sama5/sam_ssc.h (limited to 'nuttx') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index f972f9ad0..5085fa5ee 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -5984,4 +5984,8 @@ * include/nuttx/audio/i2s.h: First cut at an I2S interface definition. This initial definition is sparse will will probably evolve significantly (2011-11-7). + * arch/arm/src/sama5/sam_ssc.c and .h: Skeleton and build setup + for a forthcoming SSC (aka I2S) driver for the SAMA5. The + initial check-in is just the SAMA5 SPI driver gutted and hacked + to use the I2S interface. More coming (2013-11-7). diff --git a/nuttx/Kconfig b/nuttx/Kconfig index 7ea297a4e..3b588dd96 100644 --- a/nuttx/Kconfig +++ b/nuttx/Kconfig @@ -481,6 +481,15 @@ config DEBUG_SPI Support for this debug option is architecture-specific and may not be available for some MCUs. +config DEBUG_I2S + bool "I2S Debug Output" + default n + depends on I2S + ---help--- + Enable I2S driver debug SYSLOG output (disabled by default). + Support for this debug option is architecture-specific and may not + be available for some MCUs. + config DEBUG_CAN bool "CAN Debug Output" default n diff --git a/nuttx/arch/arm/src/sama5/Kconfig b/nuttx/arch/arm/src/sama5/Kconfig index 86383e8d0..eaba1681b 100644 --- a/nuttx/arch/arm/src/sama5/Kconfig +++ b/nuttx/arch/arm/src/sama5/Kconfig @@ -249,10 +249,12 @@ config SAMA5_ISI config SAMA5_SSC0 bool "Synchronous Serial Controller 0 (SSC0)" default n + select I2S config SAMA5_SSC1 bool "Synchronous Serial Controller 1 (SSC1)" default n + select I2S config SAMA5_CAN0 bool "CAN controller 0 (CAN0)" @@ -1373,6 +1375,238 @@ config SAMA5_TWI_REGDEBUG endmenu # TWI device driver options endif # SAMA5_TWI0 || SAMA5_TWI1 || SAMA5_TWI2 +if SAMA5_SSC0 || SAMA5_SSC1 +menu "SSC Configuration" + +config SAMA5_SSC_DMA + bool "Enable SSC DMA" + default n + depends on (SAMA5_DMAC0 && SAMA5_SSC0) || (SAMA5_DMAC1 && SAMA5_SSC1) + ---help--- + Enable use of DMA in I2C tranfers + +config SAMA5_SSC_DMATHRESHOLD + int "DMA transfer threshold" + default 4 + depends on SAMA5_SSC_DMA + ---help--- + Small I2S transfers are better performed without using DMA. This + setting defines a threshold to select when small transfer should + be performed without using DMA. + +if SAMA5_SSC0 +comment "SSC0 Configuration" + +config SAMA5_SSC0_RX + bool "Enable I2C receive" + default n + ---help--- + Enable I2S receipt logic + +if SAMA5_SSC0_RX + +choice + prompt "Receiver clock source" + default SAMA5_SSC0_RX_INTCLK + +config SAMA5_SSC0_RX_EXTCLK + bool "External Clock" + ---help--- + The SSC receiver clock is an external clock provided on the RK input + pin. + +config SAMA5_SSC0_RX_TXCLK + bool "Transmitter Clock" + ---help--- + The SSC receiver clock is transmitter clock. + +config SAMA5_SSC0_RX_INTCLK + bool "MCK/2" + ---help--- + The SSC receiver clock is the MCK/2 divided by a up to 4095. + +endchoice # Receiver clock source + +config SAMA5_SSC0_RX_EXTFREQ + int "External reciver clock frequency" + default 100 + depends on SAMA5_SSC0_RX_EXTCLK + ---help--- + If the receiver clock is provided via a clock input on the RK pin, + then the frequency of the receiver clock must be provided. + +endif # SAMA5_SSC0_RX + +config SAMA5_SSC0_TX + bool "Enable I2C transmit" + default n + ---help--- + Enable I2S transmission logic + +if SAMA5_SSC0_TX + +choice + prompt "Transmitter clock source" + default SAMA5_SSC0_TX_INTCLK + +config SAMA5_SSC0_TX_EXTCLK + bool "External Clock" + ---help--- + The SSC transmitter clock is an external clock provided on the TK input + pin. + +config SAMA5_SSC0_TX_RXCLK + bool "Receiver Clock" + ---help--- + The SSC transmitter clock is receiver clock. + +config SAMA5_SSC0_TX_INTCLK + bool "MCK/2" + ---help--- + The SSC transmitter clock is the MCK/2 divided by a up to 4095. + +endchoice # Transmitter clock source + +config SAMA5_SSC0_TX_EXTFREQ + int "External transmitter clock frequency" + default 100 + depends on SAMA5_SSC0_TX_EXTCLK + ---help--- + If the transmitter clock is provided via a clock input on the TK pin, + then the frequency of the transmitter clock must be provided. + +endif # SAMA5_SSC0_TX + +config SAMA5_SSC0_TX_INTCLK_FREQUENCY + int "Internal transmitter clock frequency" + default 100 + depends on SAMA5_SSC0_RX_INTCLK || SAMA5_SSC0_TX_INTCLK + ---help--- + If the either the receiver or transmitter clock is provided by MCK/2 divided + down, then the target frequency must be provided. The SSC driver will + determine the best divider to obtain that frequency (up to 4095). If the + frequency is too low to be obtained by dividing down the MCK/2, a compile + time error will occur. + +endif # SAMA5_SSC0 + +if SAMA5_SSC1 +comment "SSC1 Configuration" + +config SAMA5_SSC1_RX + bool "Enable I2C receive" + default n + ---help--- + Enable I2S receipt logic + +if SAMA5_SSC1_RX + +choice + prompt "Receiver clock source" + default SAMA5_SSC1_RX_INTCLK + +config SAMA5_SSC1_RX_EXTCLK + bool "External Clock" + ---help--- + The SSC receiver clock is an external clock provided on the RK input + pin. + +config SAMA5_SSC1_RX_TXCLK + bool "Transmitter Clock" + ---help--- + The SSC receiver clock is transmitter clock. + +config SAMA5_SSC1_RX_INTCLK + bool "MCK/2" + ---help--- + The SSC receiver clock is the MCK/2 divided by a up to 4095. + +endchoice # Receiver clock source + +config SAMA5_SSC1_RX_EXTFREQ + int "External reciver clock frequency" + default 100 + depends on SAMA5_SSC1_RX_EXTCLK + ---help--- + If the receiver clock is provided via a clock input on the RK pin, + then the frequency of the receiver clock must be provided. + +endif # SAMA5_SSC0_RX + +config SAMA5_SSC1_TX + bool "Enable I2C transmit" + default n + ---help--- + Enable I2S transmission logic + +if SAMA5_SSC1_TX + +choice + prompt "Transmitter clock source" + default SAMA5_SSC1_TX_INTCLK + +config SAMA5_SSC1_TX_EXTCLK + bool "External Clock" + ---help--- + The SSC transmitter clock is an external clock provided on the TK input + pin. + +config SAMA5_SSC1_TX_RXCLK + bool "Receiver Clock" + ---help--- + The SSC transmitter clock is receiver clock. + +config SAMA5_SSC1_TX_INTCLK + bool "MCK/2" + ---help--- + The SSC transmitter clock is the MCK/2 divided by a up to 4095. + +endchoice # Transmitter clock source + +config SAMA5_SSC1_TX_EXTFREQ + int "External transmitter clock frequency" + default 100 + depends on SAMA5_SSC1_TX_EXTCLK + ---help--- + If the transmitter clock is provided via a clock input on the TK pin, + then the frequency of the transmitter clock must be provided. + +endif # SAMA5_SSC1_TX + +config SAMA5_SSC1_TX_INTCLK_FREQUENCY + int "Internal transmitter clock frequency" + default 100 + depends on SAMA5_SSC1_RX_INTCLK || SAMA5_SSC1_TX_INTCLK + ---help--- + If the either the receiver or transmitter clock is provided by MCK/2 divided + down, then the target frequency must be provided. The SSC driver will + determine the best divider to obtain that frequency (up to 4095). If the + frequency is too low to be obtained by dividing down the MCK/2, a compile + time error will occur. + +endif # SAMA5_SSC1 + +config SAMA5_SSC_DMADEBUG + bool "SSC DMA transfer debug" + depends on SAMA5_SSC_DMA && DEBUG && DEBUG_DMA + default n + ---help--- + Enable special debug instrumentation analyze SSC DMA data transfers. + This logic is as non-invasive as possible: It samples DMA + registers at key points in the data transfer and then dumps all of + the registers at the end of the transfer. + +config SAMA5_SSC_REGDEBUG + bool "SSC Register level debug" + depends on DEBUG + default n + ---help--- + Output detailed register-level SSC device debug information. + Very invasive! Requires also DEBUG. + +endmenu # SSC Configuration +endif # SAMA5_SSC0 || SAMA5_SSC1 + if SAMA5_HSMCI0 || SAMA5_HSMCI1 || SAMA5_HSMCI2 menu "HSMCI device driver options" diff --git a/nuttx/arch/arm/src/sama5/Make.defs b/nuttx/arch/arm/src/sama5/Make.defs index bd765e841..86c275405 100644 --- a/nuttx/arch/arm/src/sama5/Make.defs +++ b/nuttx/arch/arm/src/sama5/Make.defs @@ -131,6 +131,15 @@ else endif endif +ifeq ($(CONFIG_SAMA5_SSC0),y) +CHIP_CSRCS += sam_ssc.c +else +ifeq ($(CONFIG_SAMA5_SSC1),y) +CHIP_CSRCS += sam_ssc.c +else +endif +endif + ifeq ($(CONFIG_SAMA5_LCDC),y) CHIP_CSRCS += sam_lcd.c endif diff --git a/nuttx/arch/arm/src/sama5/chip/sam_ssc.h b/nuttx/arch/arm/src/sama5/chip/sam_ssc.h index 68fd3a77f..e8de5d1fb 100644 --- a/nuttx/arch/arm/src/sama5/chip/sam_ssc.h +++ b/nuttx/arch/arm/src/sama5/chip/sam_ssc.h @@ -68,7 +68,7 @@ #define SAM_SSC_IMR_OFFSET 0x004c /* Interrupt Mask Register */ #define SAM_SSC_WPMR_OFFSET 0x00e4 /* Write Protect Mode Register */ #define SAM_SSC_WPSR_OFFSET 0x00e8 /* Write Protect Status Register */ - /* 0x50-0x124 Reserved + /* 0x50-0x124 Reserved */ /* SSC Register Addresses ***********************************************************/ @@ -193,9 +193,9 @@ #define SSC_TCMR_CKS_SHIFT (0) /* Bits 0-1: Transmit Clock Selection */ #define SSC_TCMR_CKS_MASK (3 << SSC_TCMR_CKS_SHIFT) -# define SSC_TCMR_CKS_ MCK (0 << SSC_TCMR_CKS_SHIFT) /* Divided Clock */ -# define SSC_TCMR_CKS_ RK (1 << SSC_TCMR_CKS_SHIFT) /* RK Clock signal */ -# define SSC_TCMR_CKS_ TK (2 << SSC_TCMR_CKS_SHIFT) /* TK pin */ +# define SSC_TCMR_CKS_MCK (0 << SSC_TCMR_CKS_SHIFT) /* Divided Clock */ +# define SSC_TCMR_CKS_RK (1 << SSC_TCMR_CKS_SHIFT) /* RK Clock signal */ +# define SSC_TCMR_CKS_TK (2 << SSC_TCMR_CKS_SHIFT) /* TK pin */ #define SSC_TCMR_CKO_SHIFT (2) /* Bits 2-3: Transmit Clock Output Mode Selection */ #define SSC_TCMR_CKO_MASK (3 << SSC_TCMR_CKO_SHIFT) # define SSC_TCMR_CKO_NONE (0 << SSC_TCMR_CKO_SHIFT) /* None, TK pin is an input */ diff --git a/nuttx/arch/arm/src/sama5/sam_ssc.c b/nuttx/arch/arm/src/sama5/sam_ssc.c new file mode 100644 index 000000000..884c271ff --- /dev/null +++ b/nuttx/arch/arm/src/sama5/sam_ssc.c @@ -0,0 +1,1052 @@ +/**************************************************************************** + * arch/arm/src/sama5/sam_ssc.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Authors: 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include "up_internal.h" +#include "up_arch.h" + +#include "chip.h" +#include "sam_pio.h" +#include "sam_dmac.h" +#include "sam_memories.h" +#include "sam_periphclks.h" +#include "sam_ssc.h" +#include "chip/sam_pmc.h" +#include "chip/sam_ssc.h" +#include "chip/sam_pinmap.h" + +#if defined(CONFIG_SAMA5_SSC0) || defined(CONFIG_SAMA5_SSC1) + +/**************************************************************************** + * Definitions + ****************************************************************************/ +/* Configuration ************************************************************/ +/* When SSC DMA is enabled, small DMA transfers will still be performed by + * polling logic. But we need a threshold value to determine what is small. + * That value is provided by CONFIG_SAMA5_SSC_DMATHRESHOLD. + */ + +#ifndef CONFIG_SAMA5_SSC_DMATHRESHOLD +# define CONFIG_SAMA5_SSC_DMATHRESHOLD 4 +#endif + +#ifdef CONFIG_SAMA5_SSC_DMA + +# if defined(CONFIG_SAMA5_SSC0) && defined(CONFIG_SAMA5_DMAC0) +# define SAMA5_SSC0_DMA true +# else +# define SAMA5_SSC0_DMA false +# endif + +# if defined(CONFIG_SAMA5_SSC1) && defined(CONFIG_SAMA5_DMAC1) +# define SAMA5_SSC1_DMA true +# else +# define SAMA5_SSC1_DMA false +# endif +#endif + +#ifndef CONFIG_SAMA5_SSC_DMA +# undef CONFIG_SAMA5_SSC_DMADEBUG +#endif + +/* Clocking *****************************************************************/ +/* Select MCU-specific settings + * + * SSC is driven by the main clock. + */ + +#define SAM_SSC_CLOCK BOARD_MCK_FREQUENCY + +/* DMA timeout. The value is not critical; we just don't want the system to + * hang in the event that a DMA does not finish. This is set to + */ + +#define DMA_TIMEOUT_MS (800) +#define DMA_TIMEOUT_TICKS ((DMA_TIMEOUT_MS + (MSEC_PER_TICK-1)) / MSEC_PER_TICK) + +/* Debug *******************************************************************/ +/* Check if SSC debut is enabled (non-standard.. no support in + * include/debug.h + */ + +#ifndef CONFIG_DEBUG +# undef CONFIG_DEBUG_VERBOSE +# undef CONFIG_DEBUG_I2S +# undef CONFIG_SAMA5_SSC_DMADEBUG +# undef CONFIG_SAMA5_SSC_REGDEBUG +#endif + +#ifndef CONFIG_DEBUG_DMA +# undef CONFIG_SAMA5_SSC_DMADEBUG +#endif + +#ifdef CONFIG_DEBUG_I2S +# define i2sdbg lldbg +# ifdef CONFIG_DEBUG_VERBOSE +# define i2svdbg lldbg +# else +# define i2svdbg(x...) +# endif +#else +# define i2sdbg(x...) +# define i2svdbg(x...) +#endif + +#define DMA_INITIAL 0 +#define DMA_AFTER_SETUP 1 +#define DMA_AFTER_START 2 +#define DMA_CALLBACK 3 +#define DMA_TIMEOUT 3 +#define DMA_END_TRANSFER 4 +#define DMA_NSAMPLES 5 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* The state of the one SSC peripheral */ + +struct sam_i2s_s +{ + struct i2s_dev_s dev; /* Externally visible I2S interface */ + uint32_t base; /* SSC controller register base address */ + sem_t exclsem; /* Assures mutually exclusive acess to SSC */ +#if defined(CONFIG_SAMA5_SSC0) || defined(CONFIG_SAMA5_SSC1) + uint8_t i2sno; /* SSC controller number (0 or 1) */ +#endif + +#ifdef CONFIG_SAMA5_SSC_DMA + uint8_t pid; /* Peripheral ID */ + bool candma; /* DMA is supported */ + sem_t dmawait; /* Used to wait for DMA completion */ + WDOG_ID dmadog; /* Watchdog that handles DMA timeouts */ + int result; /* DMA result */ + DMA_HANDLE rxdma; /* SSC RX DMA handle */ + DMA_HANDLE txdma; /* SSC TX DMA handle */ +#endif + + /* Debug stuff */ + +#ifdef CONFIG_SAMA5_SSC_REGDEBUG + bool wr; /* Last was a write */ + uint32_t regaddr; /* Last address */ + uint32_t regval; /* Last value */ + int count; /* Number of times */ +#endif + +#ifdef CONFIG_SAMA5_SSC_DMADEBUG + struct sam_dmaregs_s rxdmaregs[DMA_NSAMPLES]; + struct sam_dmaregs_s txdmaregs[DMA_NSAMPLES]; +#endif +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Helpers */ + +#ifdef CONFIG_SAMA5_SSC_REGDEBUG +static bool i2s_checkreg(struct sam_i2s_s *i2s, bool wr, uint32_t value, + uint32_t address); +#else +# define i2s_checkreg(i2s,wr,value,address) (false) +#endif + +static inline uint32_t i2s_getreg(struct sam_i2s_s *i2s, unsigned int offset); +static inline void i2s_putreg(struct sam_i2s_s *i2s, uint32_t value, + unsigned int offset); +#ifdef CONFIG_SAMA5_SSC_DMA +static inline uintptr_t i2s_physregaddr(struct sam_i2s_s *i2s, + unsigned int offset); +#endif +#if defined(CONFIG_DEBUG_I2S) && defined(CONFIG_DEBUG_VERBOSE) +static void i2s_dumpregs(struct sam_i2s_s *i2s, const char *msg); +#else +# define i2s_dumpregs(i2s,msg) +#endif + +/* DMA support */ + +#if defined(CONFIG_SAMA5_SSC_DMADEBUG) +# define i2s_rxdma_sample(s,i) sam_dmasample((s)->rxdma, &(s)->rxdmaregs[i]) +# define i2s_txdma_sample(s,i) sam_dmasample((s)->txdma, &(s)->txdmaregs[i]) +static void i2s_dma_sampleinit(struct sam_i2s_s *i2s); +static void i2s_dma_sampledone(struct sam_i2s_s *i2s); + +#else +# define i2s_rxdma_sample(s,i) +# define i2s_txdma_sample(s,i) +# define i2s_dma_sampleinit(s) +# define i2s_dma_sampledone(s) + +#endif + +#ifdef CONFIG_SAMA5_SSC_DMA +static void i2s_rxcallback(DMA_HANDLE handle, void *arg, int result); +static void i2s_txcallback(DMA_HANDLE handle, void *arg, int result); +#endif + +/* I2S methods */ + +static uint32_t i2s_frequency(FAR struct i2s_dev_s *dev, uint32_t frequency); +#ifdef CONFIG_SAMA5_SSC_DMA +static void i2s_send_nodma(FAR struct i2s_dev_s *dev, + FAR const void *buffer, size_t nbytes); +static void i2s_receive_nodma(FAR struct i2s_dev_s *dev, FAR void *buffer, + size_t nbytes); +#endif +static void i2s_send(struct i2s_dev_s *dev, + const void *buffer, size_t nbytes); +static void i2s_receive(struct i2s_dev_s *dev, void *buffer, + size_t nbytes); + +/* Initialization */ + +#ifdef CONFIG_SAMA5_SSC0 +static void i2s_ssc0_configure(struct sam_i2s_s *i2s); +#endif +#ifdef CONFIG_SAMA5_SSC1 +static void i2s_ssc1_configure(struct sam_i2s_s *i2s); +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ +/* I2S device operations */ + +static const struct i2s_ops_s g_i2sops = +{ + .i2s_frequency = i2s_frequency, + .i2s_send = i2s_send, + .i2s_receive = i2s_receive, +}; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: i2s_checkreg + * + * Description: + * Check if the current register access is a duplicate of the preceding. + * + * Input Parameters: + * value - The value to be written + * address - The address of the register to write to + * + * Returned Value: + * true: This is the first register access of this type. + * flase: This is the same as the preceding register access. + * + ****************************************************************************/ + +#ifdef CONFIG_SAMA5_SSC_REGDEBUG +static bool i2s_checkreg(struct sam_i2s_s *i2s, bool wr, uint32_t value, + uint32_t address) +{ + if (wr == i2s->wr && /* Same kind of access? */ + value == i2s->regval && /* Same value? */ + address == i2s->regaddr) /* Same address? */ + { + /* Yes, then just keep a count of the number of times we did this. */ + + i2s->count++; + return false; + } + else + { + /* Did we do the previous operation more than once? */ + + if (i2s->count > 0) + { + /* Yes... show how many times we did it */ + + lldbg("...[Repeats %d times]...\n", i2s->count); + } + + /* Save information about the new access */ + + i2s->wr = wr; + i2s->regval = value; + i2s->regaddr = address; + i2s->count = 0; + } + + /* Return true if this is the first time that we have done this operation */ + + return true; +} +#endif + +/**************************************************************************** + * Name: i2s_getreg + * + * Description: + * Read an SSC register + * + ****************************************************************************/ + +static inline uint32_t i2s_getreg(struct sam_i2s_s *i2s, + unsigned int offset) +{ + uint32_t address = i2s->base + offset; + uint32_t value = getreg32(address); + +#ifdef CONFIG_SAMA5_SSC_REGDEBUG + if (i2s_checkreg(i2s, false, value, address)) + { + lldbg("%08x->%08x\n", address, value); + } +#endif + + return value; +} + +/**************************************************************************** + * Name: i2s_putreg + * + * Description: + * Write a value to an SSC register + * + ****************************************************************************/ + +static inline void i2s_putreg(struct sam_i2s_s *i2s, uint32_t value, + unsigned int offset) +{ + uint32_t address = i2s->base + offset; + +#ifdef CONFIG_SAMA5_SSC_REGDEBUG + if (i2s_checkreg(i2s, true, value, address)) + { + lldbg("%08x<-%08x\n", address, value); + } +#endif + + putreg32(value, address); +} + +/**************************************************************************** + * Name: i2s_physregaddr + * + * Description: + * Return the physical address of an HSMCI register + * + ****************************************************************************/ + +#ifdef CONFIG_SAMA5_SSC_DMA +static inline uintptr_t i2s_physregaddr(struct sam_i2s_s *i2s, + unsigned int offset) +{ + return sam_physregaddr(i2s->base + offset); +} +#endif + +/**************************************************************************** + * Name: i2s_dumpregs + * + * Description: + * Dump the contents of all SSC registers + * + * Input Parameters: + * i2s - The SSC controller to dump + * msg - Message to print before the register data + * + * Returned Value: + * None + * + ****************************************************************************/ + +#if defined(CONFIG_DEBUG_I2S) && defined(CONFIG_DEBUG_VERBOSE) +static void i2s_dumpregs(struct sam_i2s_s *i2s, const char *msg) +{ + i2svdbg("SSC%d: %s\n", i2s->i2sno, msg); + i2svdbg(" CMR:%08x RCMR:%08x RFMR:%08x TCMR:%08x\n", + getreg32(i2s->base + SAM_SSC_CMR_OFFSET), + getreg32(i2s->base + SAM_SSC_RCMR_OFFSET), + getreg32(i2s->base + SAM_SSC_RFMR_OFFSET), + getreg32(i2s->base + SAM_SSC_TCMR_OFFSET)); + i2svdbg(" TFMR:%08x RC0R:%08x RC1R:%08x SR:%08x\n", + getreg32(i2s->base + SAM_SSC_TFMR_OFFSET), + getreg32(i2s->base + SAM_SSC_RC0R_OFFSET), + getreg32(i2s->base + SAM_SSC_RC1R_OFFSET), + getreg32(i2s->base + SAM_SSC_SR_OFFSET)); + i2svdbg(" IMR:%08x WPMR:%08x WPSR:%08x\n", + getreg32(i2s->base + SAM_SSC_IMR_OFFSET), + getreg32(i2s->base + SAM_SSC_WPMR_OFFSET), + getreg32(i2s->base + SAM_SSC_WPSR_OFFSET)); +} +#endif + +/**************************************************************************** + * Name: i2s_dma_sampleinit + * + * Description: + * Initialize sampling of DMA registers (if CONFIG_SAMA5_SSC_DMADEBUG) + * + * Input Parameters: + * i2s - Chip select doing the DMA + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_SAMA5_SSC_DMADEBUG +static void i2s_dma_sampleinit(struct sam_i2s_s *i2s) +{ + /* Put contents of register samples into a known state */ + + memset(i2s->rxdmaregs, 0xff, DMA_NSAMPLES * sizeof(struct sam_dmaregs_s)); + memset(i2s->txdmaregs, 0xff, DMA_NSAMPLES * sizeof(struct sam_dmaregs_s)); + + /* Then get the initial samples */ + + sam_dmasample(i2s->rxdma, &i2s->rxdmaregs[DMA_INITIAL]); + sam_dmasample(i2s->txdma, &i2s->txdmaregs[DMA_INITIAL]); +} +#endif + +/**************************************************************************** + * Name: i2s_dma_sampledone + * + * Description: + * Dump sampled DMA registers + * + * Input Parameters: + * i2s - Chip select doing the DMA + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_SAMA5_SSC_DMADEBUG +static void i2s_dma_sampledone(struct sam_i2s_s *i2s) +{ + /* Sample the final registers */ + + sam_dmasample(i2s->rxdma, &i2s->rxdmaregs[DMA_END_TRANSFER]); + sam_dmasample(i2s->txdma, &i2s->txdmaregs[DMA_END_TRANSFER]); + + /* Then dump the sampled DMA registers */ + /* Initial register values */ + + sam_dmadump(i2s->txdma, &i2s->txdmaregs[DMA_INITIAL], + "TX: Initial Registers"); + sam_dmadump(i2s->rxdma, &i2s->rxdmaregs[DMA_INITIAL], + "RX: Initial Registers"); + + /* Register values after DMA setup */ + + sam_dmadump(i2s->txdma, &i2s->txdmaregs[DMA_AFTER_SETUP], + "TX: After DMA Setup"); + sam_dmadump(i2s->rxdma, &i2s->rxdmaregs[DMA_AFTER_SETUP], + "RX: After DMA Setup"); + + /* Register values after DMA start */ + + sam_dmadump(i2s->txdma, &i2s->txdmaregs[DMA_AFTER_START], + "TX: After DMA Start"); + sam_dmadump(i2s->rxdma, &i2s->rxdmaregs[DMA_AFTER_START], + "RX: After DMA Start"); + + /* Register values at the time of the TX and RX DMA callbacks + * -OR- DMA timeout. + * + * If the DMA timedout, then there will not be any RX DMA + * callback samples. There is probably no TX DMA callback + * samples either, but we don't know for sure. + */ + + sam_dmadump(i2s->txdma, &i2s->txdmaregs[DMA_CALLBACK], + "TX: At DMA callback"); + + /* Register values at the end of the DMA */ + + if (i2s->result == -ETIMEDOUT) + { + sam_dmadump(i2s->rxdma, &i2s->rxdmaregs[DMA_TIMEOUT], + "RX: At DMA timeout"); + } + else + { + sam_dmadump(i2s->rxdma, &i2s->rxdmaregs[DMA_CALLBACK], + "RX: At DMA callback"); + } + + sam_dmadump(i2s->rxdma, &i2s->rxdmaregs[DMA_END_TRANSFER], + "RX: At End-of-Transfer"); + sam_dmadump(i2s->txdma, &i2s->txdmaregs[DMA_END_TRANSFER], + "TX: At End-of-Transfer"); +} +#endif + +/**************************************************************************** + * Name: i2s_dmatimeout + * + * Description: + * The watchdog timeout setup when a has expired without completion of a + * DMA. + * + * Input Parameters: + * argc - The number of arguments (should be 1) + * arg - The argument (state structure reference cast to uint32_t) + * + * Returned Value: + * None + * + * Assumptions: + * Always called from the interrupt level with interrupts disabled. + * + ****************************************************************************/ + +#ifdef CONFIG_SAMA5_SSC_DMA +static void i2s_dmatimeout(int argc, uint32_t arg) +{ + struct sam_i2s_s *i2s = (struct sam_i2s_s *)arg; + DEBUGASSERT(i2s != NULL); + + /* Sample DMA registers at the time of the timeout */ + + i2s_rxdma_sample(i2s, DMA_CALLBACK); + + /* Report timeout result, perhaps overwriting any failure reports from + * the TX callback. + */ + + i2s->result = -ETIMEDOUT; + + /* Then wake up the waiting thread */ + + sem_post(&i2s->dmawait); +} +#endif + +/**************************************************************************** + * Name: i2s_rxcallback + * + * Description: + * This callback function is invoked at the completion of the SSC RX DMA. + * + * Input Parameters: + * handle - The DMA handler + * arg - A pointer to the chip select struction + * result - The result of the DMA transfer + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_SAMA5_SSC_DMA +static void i2s_rxcallback(DMA_HANDLE handle, void *arg, int result) +{ + struct sam_i2s_s *i2s = (struct sam_i2s_s *)arg; + DEBUGASSERT(i2s != NULL); + + /* Cancel the watchdog timeout */ + + (void)wd_cancel(i2s->dmadog); + + /* Sample DMA registers at the time of the callback */ + + i2s_rxdma_sample(i2s, DMA_CALLBACK); + + /* Report the result of the transfer only if the TX callback has not already + * reported an error. + */ + + if (i2s->result == -EBUSY) + { + /* Save the result of the transfer if no error was previuosly reported */ + + i2s->result = result; + } + + /* Then wake up the waiting thread */ + + sem_post(&i2s->dmawait); +} +#endif + +/**************************************************************************** + * Name: i2s_txcallback + * + * Description: + * This callback function is invoked at the completion of the SSC TX DMA. + * + * Input Parameters: + * handle - The DMA handler + * arg - A pointer to the chip select struction + * result - The result of the DMA transfer + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_SAMA5_SSC_DMA +static void i2s_txcallback(DMA_HANDLE handle, void *arg, int result) +{ + struct sam_i2s_s *i2s = (struct sam_i2s_s *)arg; + DEBUGASSERT(i2s != NULL); + + i2s_txdma_sample(i2s, DMA_CALLBACK); + + /* Do nothing on the TX callback unless an error is reported. This + * callback is not really important because the SSC exchange is not + * complete until the RX callback is received. + */ + + if (result != OK && i2s->result == -EBUSY) + { + /* Save the result of the transfer if an error is reported */ + + i2s->result = result; + } +} +#endif + +/**************************************************************************** + * Name: i2s_frequency + * + * Description: + * Set the SSC frequency. + * + * Input Parameters: + * dev - Device-specific state data + * frequency - The SSC frequency requested + * + * Returned Value: + * Returns the actual frequency selected + * + ****************************************************************************/ + +static uint32_t i2s_frequency(struct i2s_dev_s *dev, uint32_t frequency) +{ + struct sam_i2s_s *i2s = (struct sam_i2s_s *)dev; + uint32_t actual; + uint32_t regval; + + i2svdbg("Frequency=%d\n", frequency); +#warning Missing logic + + i2sdbg("Frequency %d->%d\n", frequency, actual); + return actual; +} + +/*************************************************************************** + * Name: i2s_send_nodma + * + * Description: + * Send a block of data on SSC without using DMA + * + * Input Parameters: + * dev - Device-specific state data + * buffer - A pointer to the buffer of data to be sent + * nbytes - the length of data to send from the buffer in number of bytes. + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_SAMA5_SSC_DMA +static void i2s_send_nodma(struct i2s_dev_s *dev, const void *buffer, + size_t nbytes) +#else +static void i2s_send(struct i2s_dev_s *dev, const void *buffer, size_t nbytes) +#endif +{ + struct sam_i2s_s *i2s = (struct sam_i2s_s *)dev; + DEBUGASSERT(i2s); + + i2svdbg("buffer=%p nbytes=%d\n", buffer, (int)nbytes); +#warning Missing logic +} + +/**************************************************************************** + * Name: i2s_receive_nodma + * + * Description: + * Receive a block of data from SSC without using DMA + * + * Input Parameters: + * dev - Device-specific state data + * buffer - A pointer to the buffer in which to recieve data + * nbytes - the length of data that can be received in the buffer in number + * of bytes. + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_SAMA5_SSC_DMA +static void i2s_receive_nodma(struct i2s_dev_s *dev, void *buffer, + size_t nbytes) +#else +static void i2s_receive(struct i2s_dev_s *dev, void *buffer, size_t nbytes) +#endif +{ + struct sam_i2s_s *i2s = (struct sam_i2s_s *)dev; + DEBUGASSERT(i2s); + + i2svdbg("buffer=%p nbytes=%d\n", buffer, (int)nbytes); +#warning Missing logic +} + +/*************************************************************************** + * Name: i2s_send + * + * Description: + * Send a block of data on SSC using DMA is possible + * + * Input Parameters: + * dev - Device-specific state data + * buffer - A pointer to the buffer of data to be sent + * nbytes - the length of data to send from the buffer in number of bytes. + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_SAMA5_SSC_DMA +static void i2s_send(struct i2s_dev_s *dev, const void *buffer, size_t nbytes) +{ + struct sam_i2s_s *i2s = (struct sam_i2s_s *)dev; + DEBUGASSERT(i2s); + + i2svdbg("buffer=%p nbytes=%d\n", buffer, (int)nbytes); + + /* If we are not configured to do DMA OR is this is a very small transfer, + * then defer the operation to i2s_send_nodma(). + */ + + if (!i2s->candma || nbytes < CONFIG_SAMA5_SSC_DMATHRESHOLD) + { + i2s_send_nodma(dev, buffer, nbytes); + } + + /* Otherwise, perform the transfer using DMA */ + + else + { +#warning Missing logic + } +} +#endif + +/**************************************************************************** + * Name: i2s_receive + * + * Description: + * Receive a block of data from SSC using DMA is possible + * + * Input Parameters: + * dev - Device-specific state data + * buffer - A pointer to the buffer in which to recieve data + * nbytes - the length of data that can be received in the buffer in number + * of bytes. + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_SAMA5_SSC_DMA +static void i2s_receive(struct i2s_dev_s *dev, void *buffer, size_t nbytes) +{ + struct sam_i2s_s *i2s = (struct sam_i2s_s *)dev; + + /* If we are not configured to do DMA OR is this is a very small transfer, + * then defer the operation to i2s_send_nodma(). + */ + + if (!i2s->candma || nbytes < CONFIG_SAMA5_SSC_DMATHRESHOLD) + { + i2s_send_nodma(dev, buffer, nbytes); + } + + /* Otherwise, perform the transfer using DMA */ + + else + { +#warning Missing logic + } +} +#endif + +/**************************************************************************** + * Name: i2s_ssc0/1_configure + * + * Description: + * Configure SSC0 and/or SSC1 + * + * Input Parameters: + * i2c - Partially initialized I2C device structure. These functions + * will compolete the SSC specific portions of the initialization + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_SAMA5_SSC0 +static void i2s_ssc0_configure(struct sam_i2s_s *i2s) +{ + /* Enable clocking to the SSC0 peripheral */ + + sam_ssc0_enableclk(); + + /* Configure multiplexed pins as connected on the board. Chip + * select pins must be selected by board-specific logic. + */ + +#ifdef CONFIG_SAMA5_SSC0_RX + sam_configpio(PIO_SSC0_RD); + sam_configpio(PIO_SSC0_RF); + sam_configpio(PIO_SSC0_RK); +#ifdef CONFIG_SAMA5_SSC0_RX_EXTCLK + sam_configpio(PIO_SSC0_RK); /* External clock received on the RK I/O pad */ +#endif +#endif /* CONFIG_SAMA5_SSC0_RX */ + +#ifdef CONFIG_SAMA5_SSC0_TX + sam_configpio(PIO_SSC0_TD); + sam_configpio(PIO_SSC0_TF); +#ifdef CONFIG_SAMA5_SSC0_TX_EXTCLK + sam_configpio(PIO_SSC0_TK); /* External clock received on the TK I/O pad */ +#endif +#endif /* CONFIG_SAMA5_SSC0_TX */ + + /* Configure driver state specific to this SSC peripheral */ + + i2s->base = SAM_SSC0_VBASE; +#ifdef CONFIG_SAMA5_SSC_DMA + i2s->candma = SAMA5_SSC1_DMA; + i2s->pid = SAM_PID_SSC0; +#endif +} +#endif + +#ifdef CONFIG_SAMA5_SSC1 +static void i2s_ssc1_configure(struct sam_i2s_s *i2s) +{ + /* Enable clocking to the SSC1 peripheral */ + + sam_ssc1_enableclk(); + + /* Configure multiplexed pins as connected on the board. Chip + * select pins must be selected by board-specific logic. + */ + +#ifdef CONFIG_SAMA5_SSC1_RX + sam_configpio(PIO_SSC1_RD); + sam_configpio(PIO_SSC1_RF); +#ifdef CONFIG_SAMA5_SSC1_RX_EXTCLK + sam_configpio(PIO_SSC1_RK); /* External clock received on the RK I/O pad */ +#endif +#endif /* CONFIG_SAMA5_SSC1_RX */ + +#ifdef CONFIG_SAMA5_SSC1_TX + sam_configpio(PIO_SSC1_TD); + sam_configpio(PIO_SSC1_TF); +#ifdef CONFIG_SAMA5_SSC1_TX_EXTCLK + sam_configpio(PIO_SSC1_TK); /* External clock received on the TK I/O pad */ +#endif +#endif /* CONFIG_SAMA5_SSC1_TX */ + + /* Configure driver state specific to this SSC peripheral */ + + i2s->base = SAM_SSC1_VBASE; +#ifdef CONFIG_SAMA5_SSC_DMA + i2s->candma = SAMA5_SSC1_DMA; + i2s->pid = SAM_PID_SSC1; +#endif +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_i2sinitialize + * + * Description: + * Initialize the selected SSC port + * + * Input Parameter: + * cs - Chip select number (identifying the "logical" SSC port) + * + * Returned Value: + * Valid SSC device structure reference on succcess; a NULL on failure + * + ****************************************************************************/ + +struct i2s_dev_s *up_i2sinitialize(int port) +{ + struct sam_i2s_s *i2s; + irqstate_t flags; + + /* The support SAM parts have only a single SSC port */ + + i2svdbg("port: %d\n", port); + + /* Allocate a new state structure for this chip select. NOTE that there + * is no protection if the same chip select is used in two different + * chip select structures. + */ + + i2s = (struct sam_i2s_s *)zalloc(sizeof(struct sam_i2s_s)); + if (!i2s) + { + i2sdbg("ERROR: Failed to allocate a chip select structure\n"); + return NULL; + } + + /* Set up the initial state for this chip select structure. Other fields + * were zeroed by zalloc(). + */ + + /* Initialize the common parts for the SSC device structure */ + + sem_init(&i2s->exclsem, 0, 1); + i2s->dev.ops = &g_i2sops; + i2s->i2sno = port; + + flags = irqsave(); +#ifdef CONFIG_SAMA5_SSC0 + if (port == 0) + { + i2s_ssc0_configure(i2s); + } + else +#endif /* CONFIG_SAMA5_SSC0 */ +#ifdef CONFIG_SAMA5_SSC1 + if (port == 1) + { + i2s_ssc1_configure(i2s); + } + else +#endif /* CONFIG_SAMA5_SSC1 */ + { + i2sdbg("ERROR: Unsupported I2S port: %d\n", port); + goto errout_with_alloc; + } + +#ifdef CONFIG_SAMA5_SSC_DMA + /* Pre-allocate DMA channels. These allocations exploit that fact that + * SSC0 is managed by DMAC0 and SSC1 is managed by DMAC1. Hence, + * the SSC number (port) is the same as the DMAC number. + */ + + if (i2s->candma) + { + i2s->rxdma = sam_dmachannel(port, 0); + if (!i2s->rxdma) + { + i2sdbg("ERROR: Failed to allocate the RX DMA channel\n"); + i2s->candma = false; + } + } + + if (i2s->candma) + { + i2s->txdma = sam_dmachannel(port, 0); + if (!i2s->txdma) + { + i2sdbg("ERROR: Failed to allocate the TX DMA channel\n"); + sam_dmafree(i2s->rxdma); + i2s->rxdma = NULL; + i2s->candma = false; + } + } + + /* Initialize the SSC semaphore that is used to wake up the waiting + * thread when the DMA transfer completes. + */ + + sem_init(&i2s->dmawait, 0, 0); + + /* Create a watchdog time to catch DMA timeouts */ + + i2s->dmadog = wd_create(); + DEBUGASSERT(i2s->dmadog); +#endif + + /* Initialize I2S hardware */ +#warning "Missing logic" + irqrestore(flags); + i2s_dumpregs(i2s, "After initialization"); + + return &i2s->dev; + +errout_with_alloc: + sem_destroy(&i2s->exclsem); + kfree(i2s); + return NULL; +} + +#endif /* CONFIG_SAMA5_SSC0 || CONFIG_SAMA5_SSC1 */ diff --git a/nuttx/arch/arm/src/sama5/sam_ssc.h b/nuttx/arch/arm/src/sama5/sam_ssc.h new file mode 100644 index 000000000..b7ecafe5a --- /dev/null +++ b/nuttx/arch/arm/src/sama5/sam_ssc.h @@ -0,0 +1,102 @@ +/************************************************************************************ + * arch/arm/src/sama5/sam_ssc.h + * + * Copyright (C) 2013 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_SAMA5_SAM_SSC_H +#define __ARCH_ARM_SRC_SAMA5_SAM_SSC_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +#include "chip.h" +#include "chip/sam_ssc.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * 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_ssc_initialize + * + * Description: + * Initialize the selected I2S port. + * + * Input Parameter: + * Port number (for hardware that has mutiple I2S interfaces) + * + * Returned Value: + * Valid I2S device structure reference on succcess; a NULL on failure + * + ****************************************************************************/ + +FAR struct i2s_dev_s *sam_ssc_initialize(int port); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_ARM_SRC_SAMA5_SAM_SSC_H */ diff --git a/nuttx/drivers/Kconfig b/nuttx/drivers/Kconfig index 5fdc236f2..fa32c2b6e 100644 --- a/nuttx/drivers/Kconfig +++ b/nuttx/drivers/Kconfig @@ -161,6 +161,17 @@ if SPI source drivers/spi/Kconfig endif +menuconfig I2S + bool "I2S Driver Support" + default n + ---help--- + This selection enables selection of common I2S options. This option + should be enabled by all platforms that support I2S interfaces. + See include/nuttx/audio/i2s.h for further I2S driver information. + +if I2S +endif # I2S + menuconfig RTC bool "RTC Driver Support" default n @@ -170,10 +181,11 @@ menuconfig RTC Most RTC drivers are MCU specific and may require other specific settings. +if RTC + config RTC_DATETIME bool "Date/Time RTC Support" default n - depends on RTC ---help--- There are two general types of RTC: (1) A simple battery backed counter that keeps the time when power is down, and (2) a full @@ -182,10 +194,11 @@ config RTC_DATETIME of RTC. In this case, the RTC is used to "seed" the normal NuttX timer and the NuttX system timer provides for higher resolution time. +if !RTC_DATETIME + config RTC_HIRES bool "Hi-Res RTC Support" default n - depends on RTC && !RTC_DATETIME ---help--- If RTC_DATETIME not selected, then the simple, battery backed counter is used. There are two different implementations of such simple @@ -201,20 +214,23 @@ config RTC_HIRES config RTC_FREQUENCY int "Hi-Res RTC frequency" default 1 - depends on RTC && !RTC_DATETIME && RTC_HIRES + depends on RTC_HIRES ---help--- If RTC_HIRES is defined, then the frequency of the high resolution RTC must be provided. If RTC_HIRES is not defined, RTC_FREQUENCY is assumed to be one Hz. +endif # !RTC_DATETIME + config RTC_ALARM bool "RTC Alarm Support" default n - depends on RTC ---help--- Enable if the RTC hardware supports setting of an alarm. A callback function will be executed when the alarm goes off. +endif # RTC + menuconfig WATCHDOG bool "Watchdog Timer Support" default n @@ -224,7 +240,7 @@ menuconfig WATCHDOG information. if WATCHDOG -endif +endif # WATCHDOG menuconfig ANALOG bool "Analog Device(ADC/DAC) Support" diff --git a/nuttx/include/nuttx/audio/i2s.h b/nuttx/include/nuttx/audio/i2s.h index 026bdccb6..7f18f3e61 100644 --- a/nuttx/include/nuttx/audio/i2s.h +++ b/nuttx/include/nuttx/audio/i2s.h @@ -46,6 +46,8 @@ #include #include +#ifdef CONFIG_I2S + /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ @@ -68,7 +70,7 @@ * ****************************************************************************/ -#define I2S_FREQUENCY(d,f) ((d)->ops->frequency(d,f)) +#define I2S_FREQUENCY(d,f) ((d)->ops->i2s_frequency(d,f)) /**************************************************************************** * Name: I2S_SEND @@ -86,8 +88,7 @@ * ****************************************************************************/ -#define I2S_SEND(d,b,n) ((d)->ops->send(d,b,n)) -#endif +#define I2S_SEND(d,b,n) ((d)->ops->i2s_send(d,b,n)) /**************************************************************************** * Name: I2S_RECEIVE @@ -106,7 +107,7 @@ * ****************************************************************************/ -#define I2S_RECEIVE(d,b,n) ((d)->ops->recvblock(d,b,n)) +#define I2S_RECEIVE(d,b,n) ((d)->ops->i2s_receive(d,b,n)) /**************************************************************************** * Public Types @@ -117,11 +118,11 @@ struct i2s_dev_s; struct i2s_ops_s { - uint32_t (*frequency)(FAR struct i2s_dev_s *dev, uint32_t frequency); - void (*send)(FAR struct i2s_dev_s *dev, FAR const void *buffer, - size_t nbytes); - void (*receive)(FAR struct i2s_dev_s *dev, FAR void *buffer, - size_t nbytes); + uint32_t (*i2s_frequency)(FAR struct i2s_dev_s *dev, uint32_t frequency); + void (*i2s_send)(FAR struct i2s_dev_s *dev, FAR const void *buffer, + size_t nbytes); + void (*i2s_receive)(FAR struct i2s_dev_s *dev, FAR void *buffer, + size_t nbytes); }; /* I2S private data. This structure only defines the initial fields of the @@ -135,7 +136,7 @@ struct i2s_dev_s }; /**************************************************************************** - * Public Functions + * Public Data ****************************************************************************/ #undef EXTERN @@ -148,30 +149,13 @@ extern "C" #endif /**************************************************************************** - * Name: up_i2cinitialize - * - * Description: - * Initialize the selected I2S port. - * - * This is a generic prototype for the I2S initialize logic. Specific - * architectures may support different I2S initialization functions if, - * for example, those architectures support multiple, incompatible I2S - * implementations. In any event, the prototype of those architecture- - * specific initialization functions should be the same as - * up_i2cinitialize() - * - * Input Parameter: - * Port number (for hardware that has mutiple I2S interfaces) - * - * Returned Value: - * Valid I2S device structure reference on succcess; a NULL on failure - * + * Public Functions ****************************************************************************/ -FAR struct i2s_dev_s *up_i2cinitialize(int port); - #undef EXTERN #if defined(__cplusplus) } #endif + +#endif /* CONFIG_I2S */ #endif /* __INCLUDE_NUTTX_AUDIO_I2S_H */ -- cgit v1.2.3