summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-04-01 12:13:51 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-04-01 12:13:51 -0600
commitea2f66e68f04f45959a545516e8c34f3e87f2f7e (patch)
tree5ebbae5a519e58b91a1ea56e9093ae4c06d6a51a
parenta32034559e3ba44c9a1195c6d8124d7657dc4b4b (diff)
downloadpx4-nuttx-ea2f66e68f04f45959a545516e8c34f3e87f2f7e.tar.gz
px4-nuttx-ea2f66e68f04f45959a545516e8c34f3e87f2f7e.tar.bz2
px4-nuttx-ea2f66e68f04f45959a545516e8c34f3e87f2f7e.zip
SAMV7 WM8904: Leverage WM8904 logic from the SAMA5D4-EK
-rw-r--r--nuttx/configs/sama5d4-ek/src/sama5d4-ek.h2
-rw-r--r--nuttx/configs/samv71-xult/Kconfig26
-rw-r--r--nuttx/configs/samv71-xult/README.txt22
-rw-r--r--nuttx/configs/samv71-xult/include/board.h19
-rw-r--r--nuttx/configs/samv71-xult/src/Makefile12
-rw-r--r--nuttx/configs/samv71-xult/src/sam_audio_null.c168
-rw-r--r--nuttx/configs/samv71-xult/src/sam_wm8904.c382
-rw-r--r--nuttx/configs/samv71-xult/src/samv71-xult.h134
8 files changed, 761 insertions, 4 deletions
diff --git a/nuttx/configs/sama5d4-ek/src/sama5d4-ek.h b/nuttx/configs/sama5d4-ek/src/sama5d4-ek.h
index 79c068ca3..b9c8a7262 100644
--- a/nuttx/configs/sama5d4-ek/src/sama5d4-ek.h
+++ b/nuttx/configs/sama5d4-ek/src/sama5d4-ek.h
@@ -415,7 +415,7 @@
# if !defined(CONFIG_SAMA5_PIOE_IRQ)
# warning CONFIG_SAMA5_PIOE_IRQ is required for audio support
-# undef HAVE_HSMCI
+# undef HAVE_WM8904
# endif
# ifndef CONFIG_AUDIO_FORMAT_PCM
diff --git a/nuttx/configs/samv71-xult/Kconfig b/nuttx/configs/samv71-xult/Kconfig
index b1e2cd175..b6cddcc03 100644
--- a/nuttx/configs/samv71-xult/Kconfig
+++ b/nuttx/configs/samv71-xult/Kconfig
@@ -68,4 +68,30 @@ config SAMV71XULT_HSMCI0_AUTOMOUNT_UDELAY
endif # SAMV71XULT_HSMCI0_AUTOMOUNT
+if AUDIO_WM8904
+
+config SAMV71XULT_WM8904_I2CFREQUENCY
+ int "WM8904 I2C Frequency"
+ default 400000
+ range 1 400000
+ ---help---
+ This option selects the I2C frequency to use when communicating with
+ the WM8904 device. The default, 400KHz, is the maximum supported by
+ the WM8904. If you have problems communicating with the WM8904,
+ then you might want to try lowering this rate.
+
+choice
+ prompt "WM8904 MCLK source"
+ default SAMV71XULT_WM8904_SRCMAIN
+
+config SAMV71XULT_WM8904_SRCMAIN
+ bool "Main Clock (12MHz)"
+
+config SAMV71XULT_WM8904_SRCSCK
+ bool "Slow XTAL (32.768KHz)"
+ select SAMV71XULT_SLOWCLOCK
+
+endchoice # WM8904 MCLK source
+endif # AUDIO_WM8904
+
endif # ARCH_BOARD_SAMV71_XULT
diff --git a/nuttx/configs/samv71-xult/README.txt b/nuttx/configs/samv71-xult/README.txt
index a6ec3ec1a..d1db40806 100644
--- a/nuttx/configs/samv71-xult/README.txt
+++ b/nuttx/configs/samv71-xult/README.txt
@@ -18,6 +18,7 @@ Contents
- LEDs and Buttons
- AT24MAC402 Serial EEPROM
- Networking
+ - Audio Interface
- maXTouch Xplained Pro
- Debugging
- Configurations
@@ -694,6 +695,27 @@ additional settings.
CONFIG_NSH_NETINIT_RETRYMSEC=2000 : Configure the network monitor as you like
CONFIG_NSH_NETINIT_SIGNO=18
+Audio Interface
+===============
+
+WM8904 Audio Codec
+------------------
+
+ SAMV71 Interface WM8904 Interface
+ ---- ------------ ------- ----------------------------------
+ PIO Usage Pin Function
+ ---- ------------ ------- ----------------------------------
+ PA3 TWD0 SDA I2C control interface, data line
+ PA4 TWCK0 SCLK I2C control interface, clock line
+ PA10 RD ADCDAT Digital audio output (microphone)
+ PB18 PCK2 MCLK Master clock
+ PB0 TF LRCLK Left/right data alignment clock
+ PB1 TK BCLK Bit clock, for synchronization
+ PD11 GPIO IRQ Audio interrupt
+ PD24 RF LRCLK Left/right data alignment clock
+ PD26 TD DACDAT Digital audio input (headphone)
+ ---- ------------ ------- ----------------------------------
+
maXTouch Xplained Pro
=====================
diff --git a/nuttx/configs/samv71-xult/include/board.h b/nuttx/configs/samv71-xult/include/board.h
index 64a07adab..6bcb55252 100644
--- a/nuttx/configs/samv71-xult/include/board.h
+++ b/nuttx/configs/samv71-xult/include/board.h
@@ -329,7 +329,24 @@
* There are no alternative pin selections for USART1.
*/
-/* SSC
+/* WM8904 Audio Codec
+ *
+ * SAMV71 Interface WM8904 Interface
+ * ---- ------------ ------- ----------------------------------
+ * PIO Usage Pin Function
+ * ---- ------------ ------- ----------------------------------
+ * PA3 TWD0 SDA I2C control interface, data line
+ * PA4 TWCK0 SCLK I2C control interface, clock line
+ * PA10 RD ADCDAT Digital audio output (microphone)
+ * PB18 PCK2 MCLK Master clock
+ * PB0 TF LRCLK Left/right data alignment clock
+ * PB1 TK BCLK Bit clock, for synchronization
+ * PD11 GPIO IRQ Audio interrupt
+ * PD24 RF LRCLK Left/right data alignment clock
+ * PD26 TD DACDAT Digital audio input (headphone)
+ * ---- ------------ ------- ----------------------------------
+ *
+ * SSC
*
* Alternative pin selections are available only for SSC0 TD.
* On the SAMV71-XULT board, PD26 supports the I2S TD function
diff --git a/nuttx/configs/samv71-xult/src/Makefile b/nuttx/configs/samv71-xult/src/Makefile
index 4e31999d5..0853d3bbe 100644
--- a/nuttx/configs/samv71-xult/src/Makefile
+++ b/nuttx/configs/samv71-xult/src/Makefile
@@ -86,6 +86,18 @@ ifeq ($(CONFIG_USBMSC),y)
CSRCS += sam_usbmsc.c
endif
+ifeq ($(CONFIG_AUDIO_WM8904),y)
+ifeq ($(CONFIG_SAMA5_TWI0),y)
+ifeq ($(CONFIG_SAMA5_SSC0),y)
+CSRCS += sam_wm8904.c
+endif
+endif
+endif
+
+ifeq ($(CONFIG_AUDIO_NULL),y)
+CSRCS += sam_audio_null.c
+endif
+
ifeq ($(CONFIG_MTD_CONFIG),y)
ifeq ($(CONFIG_SAMV7_TWIHS0),y)
ifeq ($(CONFIG_MTD_AT24XX),y)
diff --git a/nuttx/configs/samv71-xult/src/sam_audio_null.c b/nuttx/configs/samv71-xult/src/sam_audio_null.c
new file mode 100644
index 000000000..49c4d9546
--- /dev/null
+++ b/nuttx/configs/samv71-xult/src/sam_audio_null.c
@@ -0,0 +1,168 @@
+/************************************************************************************
+ * configs/samv71-xult/src/sam_audio_null.c
+ *
+ * Copyright (C) 2015 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.
+ *
+ ************************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <nuttx/audio/audio.h>
+#include <nuttx/audio/pcm.h>
+#include <nuttx/audio/audio_null.h>
+
+#include "samv71-xult.h"
+
+#ifdef HAVE_AUDIO_NULL
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sam_audio_null_initialize
+ *
+ * Description:
+ * Set up to use the NULL audio device for PCM unit-level testing.
+ *
+ * Input Parameters:
+ * minor - The input device minor number
+ *
+ * Returned Value:
+ * Zero is returned on success. Otherwise, a negated errno value is
+ * returned to indicate the nature of the failure.
+ *
+ ****************************************************************************/
+
+int sam_audio_null_initialize(int minor)
+{
+ FAR struct audio_lowerhalf_s *nullaudio;
+ FAR struct audio_lowerhalf_s *pcm;
+ static bool initialized = false;
+ char devname[12];
+ int ret;
+
+ auddbg("minor %d\n", minor);
+ DEBUGASSERT(minor >= 0 && minor <= 25);
+
+ /* Have we already initialized? Since we never uninitialize we must prevent
+ * multiple initializations. This is necessary, for example, when the
+ * touchscreen example is used as a built-in application in NSH and can be
+ * called numerous time. It will attempt to initialize each time.
+ */
+
+ if (!initialized)
+ {
+ /* Get a null audio interface
+ */
+
+ nullaudio = audio_null_initialize();
+ if (!nullaudio)
+ {
+ auddbg("Failed to get the NULL audio interface\n");
+ ret = -ENODEV;
+ goto errout;
+ }
+
+ /* No we can embed the null audio interface into a PCM decoder
+ * instance so that we will have a PCM front end for the NULL
+ * audio driver.
+ */
+
+ pcm = pcm_decode_initialize(nullaudio);
+ if (!pcm)
+ {
+ auddbg("ERROR: Failed create the PCM decoder\n");
+ ret = -ENODEV;
+ goto errout_with_nullaudio;
+ }
+
+ /* Create a device name */
+
+ snprintf(devname, 12, "pcm%d", minor);
+
+ /* Finally, we can register the PCM/NULL audio device. */
+
+ ret = audio_register(devname, pcm);
+ if (ret < 0)
+ {
+ auddbg("ERROR: Failed to register /dev/%s device: %d\n", devname, ret);
+ goto errout_with_pcm;
+ }
+
+ /* Now we are initialized */
+
+ initialized = true;
+ }
+
+ return OK;
+
+ /* Error exits. Unfortunately there is no mechanism in place now to
+ * recover resources from most errors on initialization failures.
+ */
+
+errout_with_nullaudio:
+errout_with_pcm:
+errout:
+ return ret;
+}
+
+#endif /* HAVE_AUDIO_NULL */
diff --git a/nuttx/configs/samv71-xult/src/sam_wm8904.c b/nuttx/configs/samv71-xult/src/sam_wm8904.c
new file mode 100644
index 000000000..cd10d72ff
--- /dev/null
+++ b/nuttx/configs/samv71-xult/src/sam_wm8904.c
@@ -0,0 +1,382 @@
+/************************************************************************************
+ * configs/samv71-xult/src/sam_wm8904.c
+ *
+ * Copyright (C) 2015 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.
+ *
+ ************************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <nuttx/i2c.h>
+#include <nuttx/audio/i2s.h>
+#include <nuttx/audio/pcm.h>
+#include <nuttx/audio/wm8904.h>
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "sam_gpio.h"
+#include "sam_twihs.h"
+#include "sam_ssc.h"
+#include "sam_pck.h"
+
+#include "samv71-xult.h"
+
+#ifdef HAVE_WM8904
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct samv7xult_mwinfo_s
+{
+ /* Standard MW8904 interface */
+
+ struct wm8904_lower_s lower;
+
+ /* Extensions for the samv7xult board */
+
+ wm8904_handler_t handler;
+ FAR void *arg;
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/* IRQ/PIO access callbacks. These operations all hidden behind
+ * callbacks to isolate the WM8904 driver from differences in PIO
+ * interrupt handling by varying boards and MCUs. If possible,
+ * interrupts should be configured on both rising and falling edges
+ * so that contact and loss-of-contact events can be detected.
+ *
+ * attach - Attach the WM8904 interrupt handler to the PIO interrupt
+ * enable - Enable or disable the PIO interrupt
+ */
+
+static int wm8904_attach(FAR const struct wm8904_lower_s *lower,
+ wm8904_handler_t isr, FAR void *arg);
+static bool wm8904_enable(FAR const struct wm8904_lower_s *lower,
+ bool enable);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* A reference to a structure of this type must be passed to the WM8904
+ * driver. This structure provides information about the configuration
+ * of the WM8904 and provides some board-specific hooks.
+ *
+ * Memory for this structure is provided by the caller. It is not copied
+ * by the driver and is presumed to persist while the driver is active.
+ */
+
+static struct samv7xult_mwinfo_s g_wm8904info =
+{
+ .lower =
+ {
+ .address = WM8904_I2C_ADDRESS,
+ .frequency = CONFIG_SAMV7D4EK_WM8904_I2CFREQUENCY,
+#ifdef CONFIG_SAMV7D4EK_WM8904_SRCSCK
+ .mclk = BOARD_SLOWCLK_FREQUENCY,
+#else
+ .mclk = BOARD_MAINCK_FREQUENCY,
+#endif
+
+ .attach = wm8904_attach,
+ .enable = wm8904_enable,
+ },
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * IRQ/PIO access callbacks. These operations all hidden behind
+ * callbacks to isolate the WM8904 driver from differences in PIO
+ * interrupt handling by varying boards and MCUs. If possible,
+ * interrupts should be configured on both rising and falling edges
+ * so that contact and loss-of-contact events can be detected.
+ *
+ * attach - Attach the WM8904 interrupt handler to the PIO interrupt
+ * enable - Enable or disable the PIO interrupt
+ * clear - Acknowledge/clear any pending PIO interrupt
+ *
+ ****************************************************************************/
+
+static int wm8904_attach(FAR const struct wm8904_lower_s *lower,
+ wm8904_handler_t isr, FAR void *arg)
+{
+ if (isr)
+ {
+ /* Just save the address of the handler and its argument for now. The
+ * new handler will called via wm8904_interrupt() when the interrupt occurs.
+ */
+
+ audvdbg("Attaching %p\n", isr);
+ g_wm8904info.handler = isr;
+ g_wm8904info.arg = arg;
+ }
+ else
+ {
+ audvdbg("Detaching %p\n", g_wm8904info.handler);
+ (void)wm8904_enable(lower, false);
+ g_wm8904info.handler = NULL;
+ g_wm8904info.arg = NULL;
+ }
+
+ return OK;
+}
+
+static bool wm8904_enable(FAR const struct wm8904_lower_s *lower, bool enable)
+{
+ static bool enabled;
+ irqstate_t flags;
+ bool ret;
+
+ /* Has the interrupt state changed */
+
+ flags = irqsave();
+ if (enable != enabled)
+ {
+ /* Enable or disable interrupts */
+
+ if (enable && g_wm8904info.handler)
+ {
+ audvdbg("Enabling\n");
+ sam_gpioirqenable(IRQ_INT_WM8904);
+ enabled = true;
+ }
+ else
+ {
+ audvdbg("Disabling\n");
+ sam_gpioirqdisable(IRQ_INT_WM8904);
+ enabled = false;
+ }
+ }
+
+ ret = enabled;
+ irqrestore(flags);
+ return ret;
+}
+
+static int wm8904_interrupt(int irq, FAR void *context)
+{
+ /* Just forward the interrupt to the WM8904 driver */
+
+ audvdbg("handler %p\n", g_wm8904info.handler);
+ if (g_wm8904info.handler)
+ {
+ return g_wm8904info.handler(&g_wm8904info.lower, g_wm8904info.arg);
+ }
+
+ /* We got an interrupt with no handler. This should not
+ * happen.
+ */
+
+ sam_gpioirqdisable(IRQ_INT_WM8904);
+ return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sam_wm8904_initialize
+ *
+ * Description:
+ * This function is called by platform-specific, setup logic to configure
+ * and register the WM8904 device. This function will register the driver
+ * as /dev/wm8904[x] where x is determined by the minor device number.
+ *
+ * Input Parameters:
+ * minor - The input device minor number
+ *
+ * Returned Value:
+ * Zero is returned on success. Otherwise, a negated errno value is
+ * returned to indicate the nature of the failure.
+ *
+ ****************************************************************************/
+
+int sam_wm8904_initialize(int minor)
+{
+ FAR struct audio_lowerhalf_s *wm8904;
+ FAR struct audio_lowerhalf_s *pcm;
+ FAR struct i2c_dev_s *i2c;
+ FAR struct i2s_dev_s *i2s;
+ static bool initialized = false;
+ char devname[12];
+ int ret;
+
+ auddbg("minor %d\n", minor);
+ DEBUGASSERT(minor >= 0 && minor <= 25);
+
+ /* Have we already initialized? Since we never uninitialize we must prevent
+ * multiple initializations. This is necessary, for example, when the
+ * touchscreen example is used as a built-in application in NSH and can be
+ * called numerous time. It will attempt to initialize each time.
+ */
+
+ if (!initialized)
+ {
+ /* Configure the WM8904 interrupt pin */
+
+ (void)sam_configgpio(GPIO_INT_WM8904);
+
+ /* Get an instance of the I2C interface for the WM8904 chip select */
+
+ i2c = up_i2cinitialize(WM8904_TWI_BUS);
+ if (!i2c)
+ {
+ auddbg("Failed to initialize TWI%d\n", WM8904_TWI_BUS);
+ ret = -ENODEV;
+ goto errout;
+ }
+
+ /* Get an instance of the I2S interface for the WM8904 data channel */
+
+ i2s = sam_ssc_initialize(WM8904_SSC_BUS);
+ if (!i2s)
+ {
+ auddbg("Failed to initialize SSC%d\n", WM8904_SSC_BUS);
+ ret = -ENODEV;
+ goto errout_with_i2c;
+ }
+
+ /* Configure the DAC master clock. This clock is provided by PCK2 (PB10)
+ * that is connected to the WM8904 MCLK.
+ */
+
+#ifdef CONFIG_SAMV7D4EK_WM8904_SRCSCK
+ /* Drive the DAC with the slow clock (32.768 KHz). The slow clock was
+ * enabled in sam_boot.c if needed.
+ */
+
+ (void)sam_pck_configure(PCK2, PCKSRC_SCK, BOARD_SLOWCLK_FREQUENCY);
+#else
+ /* Drive the DAC with the main clock (12 MHz) */
+
+ (void)sam_pck_configure(PCK2, PCKSRC_MAINCK, BOARD_MAINCK_FREQUENCY);
+#endif
+
+ /* Enable the DAC master clock */
+
+ sam_pck_enable(PCK2, true);
+
+ /* Configure WM8904 interrupts */
+
+ sam_gpioirq(GPIO_INT_WM8904);
+ ret = irq_attach(IRQ_INT_WM8904, wm8904_interrupt);
+ if (ret < 0)
+ {
+ auddbg("ERROR: Failed to attach WM8904 interrupt: %d\n", ret);
+ goto errout_with_i2s;
+ }
+
+ /* Now we can use these I2C and I2S interfaces to initialize the
+ * MW8904 which will return an audio interface.
+ */
+
+ wm8904 = wm8904_initialize(i2c, i2s, &g_wm8904info.lower);
+ if (!wm8904)
+ {
+ auddbg("Failed to initialize the WM8904\n");
+ ret = -ENODEV;
+ goto errout_with_irq;
+ }
+
+ /* No we can embed the WM8904/I2C/I2S conglomerate into a PCM decoder
+ * instance so that we will have a PCM front end for the the WM8904
+ * driver.
+ */
+
+ pcm = pcm_decode_initialize(wm8904);
+ if (!pcm)
+ {
+ auddbg("ERROR: Failed create the PCM decoder\n");
+ ret = -ENODEV;
+ goto errout_with_wm8904;
+ }
+
+ /* Create a device name */
+
+ snprintf(devname, 12, "pcm%d", minor);
+
+ /* Finally, we can register the PCM/WM8904/I2C/I2S audio device.
+ *
+ * Is anyone young enough to remember Rube Goldberg?
+ */
+
+ ret = audio_register(devname, pcm);
+ if (ret < 0)
+ {
+ auddbg("ERROR: Failed to register /dev/%s device: %d\n", devname, ret);
+ goto errout_with_pcm;
+ }
+
+ /* Now we are initialized */
+
+ initialized = true;
+ }
+
+ return OK;
+
+ /* Error exits. Unfortunately there is no mechanism in place now to
+ * recover resources from most errors on initialization failures.
+ */
+
+errout_with_pcm:
+errout_with_wm8904:
+errout_with_irq:
+ irq_detach(IRQ_INT_WM8904);
+errout_with_i2s:
+errout_with_i2c:
+errout:
+ return ret;
+}
+
+#endif /* HAVE_WM8904 */
diff --git a/nuttx/configs/samv71-xult/src/samv71-xult.h b/nuttx/configs/samv71-xult/src/samv71-xult.h
index 51b71a9d2..43a5ba635 100644
--- a/nuttx/configs/samv71-xult/src/samv71-xult.h
+++ b/nuttx/configs/samv71-xult/src/samv71-xult.h
@@ -61,6 +61,8 @@
#define HAVE_NETWORK 1
#define HAVE_MACADDR 1
#define HAVE_MTDCONFIG 1
+#define HAVE_WM8904 1
+#define HAVE_AUDIO_NULL 1
/* HSMCI */
/* Can't support MMC/SD if the card interface is not enabled */
@@ -179,6 +181,63 @@
# undef HAVE_MTDCONFIG
#endif
+/* Audio */
+/* PCM/WM8904 driver */
+
+#ifndef CONFIG_AUDIO_WM8904
+# undef HAVE_WM8904
+#endif
+
+#ifdef HAVE_WM8904
+# ifndef CONFIG_SAMV7_TWI0
+# warning CONFIG_SAMV7_TWI0 is required for audio support
+# undef HAVE_WM8904
+# endif
+
+# ifndef CONFIG_SAMV7_SSC0
+# warning CONFIG_SAMV7_SSC0 is required for audio support
+# undef HAVE_WM8904
+# endif
+
+# if !defined(CONFIG_SAMV7_PIOD_IRQ)
+# warning CONFIG_SAMV7_PIOD_IRQ is required for audio support
+# undef HAVE_WM8904
+# endif
+
+# ifndef CONFIG_AUDIO_FORMAT_PCM
+# warning CONFIG_AUDIO_FORMAT_PCM is required for audio support
+# undef HAVE_WM8904
+# endif
+
+# ifndef CONFIG_SAMV7D4EK_WM8904_I2CFREQUENCY
+# warning Defaulting to maximum WM8904 I2C frequency
+# define CONFIG_SAMV7D4EK_WM8904_I2CFREQUENCY 400000
+# endif
+
+# if CONFIG_SAMV7D4EK_WM8904_I2CFREQUENCY > 400000
+# warning WM8904 I2C frequency cannot exceed 400KHz
+# undef CONFIG_SAMV7D4EK_WM8904_I2CFREQUENCY
+# define CONFIG_SAMV7D4EK_WM8904_I2CFREQUENCY 400000
+# endif
+#endif
+
+/* PCM/null driver */
+
+#ifndef CONFIG_AUDIO_NULL
+# undef HAVE_AUDIO_NULL
+#endif
+
+#ifndef HAVE_WM8904
+# undef HAVE_AUDIO_NULL
+#endif
+
+#ifdef HAVE_AUDIO_NULL
+# ifndef CONFIG_AUDIO_FORMAT_PCM
+# warning CONFIG_AUDIO_FORMAT_PCM is required for audio support
+# undef HAVE_AUDIO_NULL
+# endif
+#endif
+
/* SAMV71-XULT GPIO Pin Definitions *************************************************/
/* Ethernet MAC.
@@ -304,10 +363,41 @@
#define GPIO_VBUSON (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | \
GPIO_PORT_PIOC | GPIO_PIN16)
-/* SPI Chip Selects
- * to be provided
+/* WM8904 Audio Codec ***************************************************************/
+/* SAMV71 Interface WM8904 Interface
+ * ---- ------------ ------- ----------------------------------
+ * PIO Usage Pin Function
+ * ---- ------------ ------- ----------------------------------
+ * PA3 TWD0 SDA I2C control interface, data line
+ * PA4 TWCK0 SCLK I2C control interface, clock line
+ * PA10 RD ADCDAT Digital audio output (microphone)
+ * PB18 PCK2 MCLK Master clock
+ * PB0 TF LRCLK Left/right data alignment clock
+ * PB1 TK BCLK Bit clock, for synchronization
+ * PD11 GPIO IRQ Audio interrupt
+ * PD24 RF LRCLK Left/right data alignment clock
+ * PD26 TD DACDAT Digital audio input (headphone)
+ * ---- ------------ ------- ----------------------------------
+ */
+
+/* Audio Interrupt. All interrupts are default, active high level. Pull down
+ * internally in the WM8904. So we want no pull-up/downs and we want to
+ * interrupt on the high level.
*/
+#define GPIO_INT_WM8904 (PIO_INPUT | PIO_CFG_DEFAULT | PIO_CFG_DEGLITCH | \
+ PIO_INT_HIGHLEVEL | PIO_PORT_PIOD | PIO_PIN11)
+#define IRQ_INT_WM8904 SAM_IRQ_PD11
+
+/* The MW8904 communicates on TWI0, I2C address 0x1a for control operations */
+
+#define WM8904_TWI_BUS 0
+#define WM8904_I2C_ADDRESS 0x1a
+
+/* The MW8904 transfers data on SSC0 */
+
+#define WM8904_SSC_BUS 0
+
/************************************************************************************
* Public Types
************************************************************************************/
@@ -519,5 +609,45 @@ bool sam_writeprotected(int slotno);
int sam_at24config(void);
#endif
+/****************************************************************************
+ * Name: sam_wm8904_initialize
+ *
+ * Description:
+ * This function is called by platform-specific, setup logic to configure
+ * and register the WM8904 device. This function will register the driver
+ * as /dev/wm8904[x] where x is determined by the minor device number.
+ *
+ * Input Parameters:
+ * minor - The input device minor number
+ *
+ * Returned Value:
+ * Zero is returned on success. Otherwise, a negated errno value is
+ * returned to indicate the nature of the failure.
+ *
+ ****************************************************************************/
+
+#ifdef HAVE_WM8904
+int sam_wm8904_initialize(int minor);
+#endif /* HAVE_WM8904 */
+
+/****************************************************************************
+ * Name: sam_audio_null_initialize
+ *
+ * Description:
+ * Set up to use the NULL audio device for PCM unit-level testing.
+ *
+ * Input Parameters:
+ * minor - The input device minor number
+ *
+ * Returned Value:
+ * Zero is returned on success. Otherwise, a negated errno value is
+ * returned to indicate the nature of the failure.
+ *
+ ****************************************************************************/
+
+#ifdef HAVE_AUDIO_NULL
+int sam_audio_null_initialize(int minor);
+#endif /* HAVE_AUDIO_NULL */
+
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_SAMV71_XULT_SRC_SAMV71_XULT_H */