summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog6
-rw-r--r--nuttx/Kconfig12
-rw-r--r--nuttx/Makefile.unix18
-rw-r--r--nuttx/Makefile.win18
-rw-r--r--nuttx/audio/Kconfig89
-rw-r--r--nuttx/audio/Makefile101
-rw-r--r--nuttx/audio/audio.c534
-rw-r--r--nuttx/audio/buffer.c165
-rw-r--r--nuttx/audio/pcm.c94
-rw-r--r--nuttx/configs/mikroe-stm32f4/src/up_nsh.c23
-rw-r--r--nuttx/drivers/Kconfig13
-rw-r--r--nuttx/drivers/Makefile1
-rw-r--r--nuttx/drivers/audio/Kconfig14
-rw-r--r--nuttx/drivers/audio/Make.defs51
-rw-r--r--nuttx/drivers/audio/vs1053.c257
-rw-r--r--nuttx/include/debug.h32
-rw-r--r--nuttx/include/nuttx/audio.h462
-rw-r--r--nuttx/include/nuttx/fs/ioctl.h7
18 files changed, 1896 insertions, 1 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 8a1553116..cf56b7291 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -4743,5 +4743,9 @@
(2013-5-19).
* arch/arm/src/stm32/stm32l15xxx_rcc.c chip/stm32_flash.h: Add RCC PLL
and FLASH configuration logic for the STM32L152X (2013-5-19).
- * nuttx/include/nuttx/usb/audio.h: Typo- and bug-fixes from Ken Pettit
+ * include/nuttx/usb/audio.h: Typo- and bug-fixes from Ken Pettit
(2013-5-19)
+ * audio/, drivers/audio, include/nuttx/audio.h: Add a new audio subsystem
+ and jVS1053 driver to NuttX. Contributed by Ken Pettit (2013-5-19).
+ * configs/miroe-stm32f4/: Add audio logic to NSH configuration. From Ken
+ Petty (2013-5-19).
diff --git a/nuttx/Kconfig b/nuttx/Kconfig
index 30178dd38..28f0464fd 100644
--- a/nuttx/Kconfig
+++ b/nuttx/Kconfig
@@ -492,6 +492,14 @@ config DEBUG_WATCHDOG
Support for this debug option is architecgture-specific and may not
be available for some MCUs.
+config DEBUG_AUDIO
+ bool "Enable Audio Device Debug Output"
+ default n
+ ---help---
+ Enable low level debug SYSLOG output from the audio subsystem and
+ device drivers. (disabled by default). Support for this debug option
+ is architecgture-specific and may not be available for some MCUs.
+
endif
config DEBUG_SYMBOLS
@@ -538,6 +546,10 @@ menu "Memory Management"
source mm/Kconfig
endmenu
+menu "Audio Support"
+source audio/Kconfig
+endmenu
+
menu "Binary Formats"
source binfmt/Kconfig
endmenu
diff --git a/nuttx/Makefile.unix b/nuttx/Makefile.unix
index b998dd358..6d78d505d 100644
--- a/nuttx/Makefile.unix
+++ b/nuttx/Makefile.unix
@@ -140,6 +140,12 @@ else
OTHERDIRS += graphics
endif
+ifeq ($(CONFIG_AUDIO),y)
+NONFSDIRS += audio
+else
+OTHERDIRS += audio
+endif
+
# CLEANDIRS are the directories that will clean in. These are
# all directories that we know about.
# KERNDEPDIRS are the directories in which we will build target dependencies.
@@ -252,6 +258,12 @@ ifeq ($(CONFIG_NX),y)
NUTTXLIBS += lib/libgraphics$(LIBEXT)
endif
+# Add libraries for the audio sub-system
+
+ifeq ($(CONFIG_AUDIO),y)
+NUTTXLIBS += lib/libaudio$(LIBEXT)
+endif
+
# LINKLIBS derives from NUTTXLIBS and is simply the same list with the subdirectory removed
LINKLIBS = $(patsubst lib/%,%,$(NUTTXLIBS))
@@ -508,6 +520,12 @@ graphics/libgraphics$(LIBEXT): context
lib/libgraphics$(LIBEXT): graphics/libgraphics$(LIBEXT)
$(Q) install graphics/libgraphics$(LIBEXT) lib/libgraphics$(LIBEXT)
+audio/libaudio$(LIBEXT): context
+ $(Q) $(MAKE) -C audio TOPDIR="$(TOPDIR)" libaudio$(LIBEXT) EXTRADEFINES=$(KDEFINE)
+
+lib/libaudio$(LIBEXT): audio/libaudio$(LIBEXT)
+ $(Q) install audio/libaudio$(LIBEXT) lib/libaudio$(LIBEXT)
+
syscall/libstubs$(LIBEXT): context
$(Q) $(MAKE) -C syscall TOPDIR="$(TOPDIR)" libstubs$(LIBEXT) EXTRADEFINES=$(KDEFINE)
diff --git a/nuttx/Makefile.win b/nuttx/Makefile.win
index 013281a41..a424580b7 100644
--- a/nuttx/Makefile.win
+++ b/nuttx/Makefile.win
@@ -133,6 +133,12 @@ else
OTHERDIRS += graphics
endif
+ifeq ($(CONFIG_AUDIO),y)
+NONFSDIRS += audio
+else
+OTHERDIRS += audio
+endif
+
# CLEANDIRS are the directories that will clean in. These are
# all directories that we know about.
# KERNDEPDIRS are the directories in which we will build target dependencies.
@@ -245,6 +251,12 @@ ifeq ($(CONFIG_NX),y)
NUTTXLIBS += lib\libgraphics$(LIBEXT)
endif
+# Add libraries for the Audio sub-system
+
+ifeq ($(CONFIG_AUDIO),y)
+NUTTXLIBS += lib\libaudio$(LIBEXT)
+endif
+
# LINKLIBS derives from NUTTXLIBS and is simply the same list with the subdirectory removed
LINKLIBS = $(patsubst lib\\%,%,$(NUTTXLIBS))
@@ -524,6 +536,12 @@ graphics\libgraphics$(LIBEXT): context
lib\libgraphics$(LIBEXT): graphics\libgraphics$(LIBEXT)
$(Q) install graphics\libgraphics$(LIBEXT) lib\libgraphics$(LIBEXT)
+audio\libaudio$(LIBEXT): context
+ $(Q) $(MAKE) -C audio TOPDIR="$(TOPDIR)" libaudio$(LIBEXT) EXTRADEFINES=$(KDEFINE)
+
+lib\libaudio$(LIBEXT): audio\libaudio$(LIBEXT)
+ $(Q) install audio\libaudio$(LIBEXT) lib\libaudio$(LIBEXT)
+
syscall\libstubs$(LIBEXT): context
$(Q) $(MAKE) -C syscall TOPDIR="$(TOPDIR)" libstubs$(LIBEXT) EXTRADEFINES=$(KDEFINE)
diff --git a/nuttx/audio/Kconfig b/nuttx/audio/Kconfig
new file mode 100644
index 000000000..a666c775f
--- /dev/null
+++ b/nuttx/audio/Kconfig
@@ -0,0 +1,89 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
+
+config AUDIO
+ bool "Audio Support"
+ default n
+ ---help---
+ Enables overall support for Audio library.
+
+if AUDIO
+
+config AUDIO_NCHANNELS
+ int "Number of Audio Channels"
+ default 2
+ ---help---
+ Stereo channel support is standard, but some systems may support 5 or 7
+ channel capability.
+
+config AUDIO_LARGE_BUFFERS
+ bool "Support Audio Buffers with greater than 65K samples"
+ default n
+ ---help---
+ By default, the Audio Pipeline Buffer uses a 16-bit max sample count, limiting
+ the number of samples per buffer to 65K. Enable this option to specify a
+ 32-bit max sample count for increased samples / buffer capability.
+ channel capability.
+
+menu "Supported Audio Formats"
+
+config AUDIO_FORMAT_PCM
+ bool "PCM Audio"
+ default y
+ ---help---
+ Build in support for PCM Audio format.
+
+config AUDIO_FORMAT_MP3
+ bool "MPEG 3 Layer 1"
+ default n
+ ---help---
+ Build in support for MP3 Audio format.
+
+config AUDIO_FORMAT_WMA
+ bool "WMA Format (see copyright notice)"
+ default n
+ ---help---
+ Add in support for Microsoft Windows Media format.
+
+config AUDIO_FORMAT_OGG_VORBIS
+ bool "Ogg Vorbis format"
+ default n
+ ---help---
+ Build in support for the Open Source Ogg Vorbis format.
+
+endmenu
+
+# These are here as placeholders of what could be added
+
+if CONFIG_AUDIO_PLANNED
+
+config AUDIO_MIXER
+ bool "Planned - Enable support for the software based Audio Mixer"
+ default n
+ ---help---
+ The Audio mixer is a software-only based component that can be used
+ to perform audio channel or device mixing.
+
+config AUDIO_MIDI_SYNTH
+ bool "Planned - Enable support for the software-based MIDI synthisizer"
+ default n
+ ---help---
+ Builds a simple MIDI synthisizer.
+
+config AUDIO_OUTPUT_JACK_CONTROL
+ bool "Planned - Enable support for output jack control"
+ default n
+ ---help---
+ Builds a simple MIDI synthisizer.
+
+config AUDIO_FONT
+ bool "Planned - Enable support for the Audio Font"
+ default n
+ ---help---
+ The Audio font provides common audio symbols.
+
+endif
+
+endif
diff --git a/nuttx/audio/Makefile b/nuttx/audio/Makefile
new file mode 100644
index 000000000..b6c111621
--- /dev/null
+++ b/nuttx/audio/Makefile
@@ -0,0 +1,101 @@
+############################################################################
+# audio/Makefile
+#
+# Copyright (C) 2013 Ken Pettit. All rights reserved.
+# Author: Ken Pettit <pettitkd@gmail.com>
+#
+# 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.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+DELIM ?= $(strip /)
+
+ifeq ($(WINTOOL),y)
+INCDIROPT = -w
+endif
+
+DEPPATH = --dep-path .
+ASRCS =
+CSRCS = audio.c buffer.c
+VPATH = .
+
+# Include support for various drivers. Each Make.defs file will add its
+# files to the source file list, add its DEPPATH info, and will add
+# the appropriate paths to the VPATH variable
+
+ifeq ($(CONFIG_AUDIO_FORMAT_PCM),y)
+ CSRCS += pcm.c
+endif
+
+ifeq ($(CONFIG_AUDIO_MIXER),y)
+ CSRCS += mixer.c
+endif
+
+ifeq ($(CONFIG_AUDIO_MIDI_SYNTH),y)
+ CSRCS += midisynth.c
+endif
+
+ifeq ($(CONFIG_AUDIO_FONT),y)
+ CSRCS += audio_font.c
+endif
+
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+BIN = libaudio$(LIBEXT)
+
+all: $(BIN)
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+$(BIN): $(OBJS)
+ $(call ARCHIVE, $@, $(OBJS))
+
+.depend: Makefile $(SRCS)
+ $(Q) $(MKDEP) $(DEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
+ $(Q) touch $@
+
+depend: .depend
+
+clean:
+ $(call DELFILE, $(BIN))
+ $(call CLEAN)
+
+distclean: clean
+ $(call DELFILE, Make.dep)
+ $(call DELFILE, .depend)
+
+-include Make.dep
diff --git a/nuttx/audio/audio.c b/nuttx/audio/audio.c
new file mode 100644
index 000000000..4457294f9
--- /dev/null
+++ b/nuttx/audio/audio.c
@@ -0,0 +1,534 @@
+/****************************************************************************
+ * audio/audio.c
+ *
+ * Copyright (C) 2013 Ken Pettit. All rights reserved.
+ * Author: Ken Pettit <pettitkd@gmail.com>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Compilation Switches
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <string.h>
+#include <semaphore.h>
+#include <fcntl.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/fs/fs.h>
+#include <nuttx/arch.h>
+#include <nuttx/audio.h>
+
+#include <arch/irq.h>
+
+#ifdef CONFIG_AUDIO
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Debug ********************************************************************/
+/* Non-standard debug that may be enabled just for testing Audio */
+
+#ifndef AUDIO_MAX_DEVICE_PATH
+# define AUDIO_MAX_DEVICE_PATH 32
+#endif
+
+/****************************************************************************
+ * Private Type Definitions
+ ****************************************************************************/
+
+/* This structure describes the state of the upper half driver */
+
+struct audio_upperhalf_s
+{
+ uint8_t crefs; /* The number of times the device has been opened */
+ volatile bool started; /* True: pulsed output is being generated */
+ sem_t exclsem; /* Supports mutual exclusion */
+ struct audio_info_s info; /* Pulsed output characteristics */
+ FAR struct audio_lowerhalf_s *dev; /* lower-half state */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static int audio_open(FAR struct file *filep);
+static int audio_close(FAR struct file *filep);
+static ssize_t audio_read(FAR struct file *filep, FAR char *buffer, size_t buflen);
+static ssize_t audio_write(FAR struct file *filep, FAR const char *buffer, size_t buflen);
+static int audio_start(FAR struct audio_upperhalf_s *upper, unsigned int oflags);
+static int audio_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static const struct file_operations g_audioops =
+{
+ audio_open, /* open */
+ audio_close, /* close */
+ audio_read, /* read */
+ audio_write, /* write */
+ 0, /* seek */
+ audio_ioctl /* ioctl */
+#ifndef CONFIG_DISABLE_POLL
+ , 0 /* poll */
+#endif
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/************************************************************************************
+ * Name: audio_open
+ *
+ * Description:
+ * This function is called whenever the Audio device is opened.
+ *
+ ************************************************************************************/
+
+static int audio_open(FAR struct file *filep)
+{
+ FAR struct inode *inode = filep->f_inode;
+ FAR struct audio_upperhalf_s *upper = inode->i_private;
+ uint8_t tmp;
+ int ret;
+
+ audvdbg("crefs: %d\n", upper->crefs);
+
+ /* Get exclusive access to the device structures */
+
+ ret = sem_wait(&upper->exclsem);
+ if (ret < 0)
+ {
+ ret = -errno;
+ goto errout;
+ }
+
+ /* Increment the count of references to the device. If this the first
+ * time that the driver has been opened for this device, then initialize
+ * the device.
+ */
+
+ tmp = upper->crefs + 1;
+ if (tmp == 0)
+ {
+ /* More than 255 opens; uint8_t overflows to zero */
+
+ ret = -EMFILE;
+ goto errout_with_sem;
+ }
+
+ /* Save the new open count on success */
+
+ upper->crefs = tmp;
+ ret = OK;
+
+errout_with_sem:
+ sem_post(&upper->exclsem);
+
+errout:
+ return ret;
+}
+
+/************************************************************************************
+ * Name: audio_close
+ *
+ * Description:
+ * This function is called when the Audio device is closed.
+ *
+ ************************************************************************************/
+
+static int audio_close(FAR struct file *filep)
+{
+ FAR struct inode *inode = filep->f_inode;
+ FAR struct audio_upperhalf_s *upper = inode->i_private;
+ int ret;
+
+ audvdbg("crefs: %d\n", upper->crefs);
+
+ /* Get exclusive access to the device structures */
+
+ ret = sem_wait(&upper->exclsem);
+ if (ret < 0)
+ {
+ ret = -errno;
+ goto errout;
+ }
+
+ /* Decrement the references to the driver. If the reference count will
+ * decrement to 0, then uninitialize the driver.
+ */
+
+ if (upper->crefs > 1)
+ {
+ upper->crefs--;
+ }
+ else
+ {
+ FAR struct audio_lowerhalf_s *lower = upper->dev;
+
+ /* There are no more references to the port */
+
+ upper->crefs = 0;
+
+ /* Disable the Audio device */
+
+ DEBUGASSERT(lower->ops->shutdown != NULL);
+ audvdbg("calling shutdown: %d\n");
+
+ lower->ops->shutdown(lower);
+ }
+ ret = OK;
+
+//errout_with_sem:
+ sem_post(&upper->exclsem);
+
+errout:
+ return ret;
+}
+
+/************************************************************************************
+ * Name: audio_read
+ *
+ * Description:
+ * A dummy read method. This is provided only to satsify the VFS layer.
+ *
+ ************************************************************************************/
+
+static ssize_t audio_read(FAR struct file *filep, FAR char *buffer, size_t buflen)
+{
+ /* Return zero -- usually meaning end-of-file */
+
+ return 0;
+}
+
+/************************************************************************************
+ * Name: audio_write
+ *
+ * Description:
+ * A dummy write method. This is provided only to satsify the VFS layer.
+ *
+ ************************************************************************************/
+
+static ssize_t audio_write(FAR struct file *filep, FAR const char *buffer, size_t buflen)
+{
+ return 0;
+}
+
+/************************************************************************************
+ * Name: audio_start
+ *
+ * Description:
+ * Handle the AUDIOIOC_START ioctl command
+ *
+ ************************************************************************************/
+
+static int audio_start(FAR struct audio_upperhalf_s *upper, unsigned int oflags)
+{
+ FAR struct audio_lowerhalf_s *lower = upper->dev;
+ int ret = OK;
+
+ DEBUGASSERT(upper != NULL && lower->ops->start != NULL);
+
+ /* Verify that the Audio is not already running */
+
+ if (!upper->started)
+ {
+ /* Invoke the bottom half method to start the pulse train */
+
+ ret = lower->ops->start(lower);
+
+ /* A return value of zero means that the pulse train was started
+ * successfully.
+ */
+
+ if (ret == OK)
+ {
+ /* Indicate that the pulse train has started */
+
+ upper->started = true;
+ }
+ }
+
+ return ret;
+}
+
+/************************************************************************************
+ * Name: audio_ioctl
+ *
+ * Description:
+ * The standard ioctl method. This is where ALL of the Audio work is done.
+ *
+ ************************************************************************************/
+
+static int audio_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
+{
+ FAR struct inode *inode = filep->f_inode;
+ FAR struct audio_upperhalf_s *upper = inode->i_private;
+ FAR struct audio_lowerhalf_s *lower = upper->dev;
+ int ret;
+
+ audvdbg("cmd: %d arg: %ld\n", cmd, arg);
+
+ /* Get exclusive access to the device structures */
+
+ ret = sem_wait(&upper->exclsem);
+ if (ret < 0)
+ {
+ return ret;
+ }
+
+ /* Handle built-in ioctl commands */
+
+ switch (cmd)
+ {
+ /* AUDIOIOC_GETCAPS - Get the audio device capabilities.
+ *
+ * ioctl argument: A pointer to the audio_caps_s structure.
+ */
+
+ case AUDIOIOC_GETCAPS:
+ {
+ FAR struct audio_caps_s *caps = (FAR struct audio_caps_s*)((uintptr_t)arg);
+ DEBUGASSERT(lower->ops->getcaps != NULL);
+
+ audvdbg("AUDIOIOC_GETCAPS: Device=%d", caps->ac_type);
+
+ /* Call the lower-half driver capabilities handler */
+ ret = lower->ops->getcaps(lower, caps->ac_type, caps);
+ }
+ break;
+
+ case AUDIOIOC_CONFIGURE:
+ {
+ FAR const struct audio_caps_s *caps = (FAR const struct audio_caps_s*)((uintptr_t)arg);
+ DEBUGASSERT(lower->ops->configure != NULL);
+
+ audvdbg("AUDIOIOC_INITIALIZE: Device=%d", caps->ac_type);
+
+ /* Call the lower-half driver configure handler */
+ ret = lower->ops->configure(lower, caps);
+ }
+ break;
+
+ case AUDIOIOC_SHUTDOWN:
+ {
+ DEBUGASSERT(lower->ops->shutdown != NULL);
+
+ audvdbg("AUDIOIOC_SHUTDOWN\n");
+
+ /* Call the lower-half driver initialize handler */
+ ret = lower->ops->shutdown(lower);
+ }
+ break;
+
+ /* AUDIOIOC_START - Start the pulsed output. The AUDIOIOC_SETCHARACTERISTICS
+ * command must have previously been sent.
+ *
+ * ioctl argument: None
+ */
+
+ case AUDIOIOC_START:
+ {
+ audvdbg("AUDIOIOC_START\n");
+ DEBUGASSERT(lower->ops->start != NULL);
+
+ /* Start the pulse train */
+
+ ret = audio_start(upper, filep->f_oflags);
+ }
+ break;
+
+ /* AUDIOIOC_STOP - Stop the pulsed output.
+ *
+ * ioctl argument: None
+ */
+
+ case AUDIOIOC_STOP:
+ {
+ audvdbg("AUDIOIOC_STOP\n");
+ DEBUGASSERT(lower->ops->stop != NULL);
+
+ if (upper->started)
+ {
+ ret = lower->ops->stop(lower);
+ upper->started = false;
+ }
+ }
+ break;
+
+ /* Any unrecognized IOCTL commands might be platform-specific ioctl commands */
+
+ default:
+ {
+ audvdbg("Forwarding unrecognized cmd: %d arg: %ld\n", cmd, arg);
+ DEBUGASSERT(lower->ops->ioctl != NULL);
+ ret = lower->ops->ioctl(lower, cmd, arg);
+ }
+ break;
+ }
+
+ sem_post(&upper->exclsem);
+ return ret;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: audio_register
+ *
+ * Description:
+ * This function binds an instance of a "lower half" audio driver with the
+ * "upper half" Audio device and registers that device so that can be used
+ * by application code.
+ *
+ * When this function is called, the "lower half" driver should be in the
+ * reset state (as if the shutdown() method had already been called).
+ *
+ * Input parameters:
+ * path - The full path to the driver to be registers in the NuttX pseudo-
+ * filesystem. The recommended convention is to name Audio drivers
+ * based on the function they provide, such as "/dev/pcm0", "/dev/mp31",
+ * etc.
+ * dev - A pointer to an instance of lower half audio driver. This instance
+ * is bound to the Audio driver and must persists as long as the driver
+ * persists.
+ *
+ * Returned Value:
+ * Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int audio_register(FAR const char *name, FAR struct audio_lowerhalf_s *dev)
+{
+ FAR struct audio_upperhalf_s *upper;
+ char path[AUDIO_MAX_DEVICE_PATH];
+ static bool dev_audio_created = false;
+ const char* devname = "/dev/audio";
+
+ /* Allocate the upper-half data structure */
+
+ upper = (FAR struct audio_upperhalf_s *)kzalloc(sizeof(struct audio_upperhalf_s));
+ if (!upper)
+ {
+ auddbg("Allocation failed\n");
+ return -ENOMEM;
+ }
+
+ /* Initialize the Audio device structure (it was already zeroed by kzalloc()) */
+
+ sem_init(&upper->exclsem, 0, 1);
+ upper->dev = dev;
+
+ /* Create a /dev/audio directory. */
+
+ if (!dev_audio_created)
+ {
+ /* We don't check for error here because even if it fails, then
+ * the register_driver call below will return an error condition
+ * for us.
+ */
+
+ mkdir(devname, 0644);
+ dev_audio_created = true;
+ }
+
+ /* Register the Audio device */
+
+ memset(path, 0, AUDIO_MAX_DEVICE_PATH);
+ strcpy(path, devname);
+ strcat(path, "/");
+ strncat(path, name, AUDIO_MAX_DEVICE_PATH - 11);
+
+ audvdbg("Registering %s\n", path);
+ return register_driver(path, &g_audioops, 0666, upper);
+}
+
+/****************************************************************************
+ * Name: audio_dequeuebuffer
+ *
+ * Description:
+ * Dequeues a previously enqueued Audio Pipeline Buffer.
+ *
+ * 1. The upper half driver calls the enqueuebuffer method, providing the
+ * lower half driver with the ab_buffer to process.
+ * 2. The lower half driver's enqueuebuffer will either processes the
+ * buffer directly, or more likely add it to a queue for processing
+ * by a background thread or worker task.
+ * 3. When the lower half driver has completed processing of the enqueued
+ * ab_buffer, it will call this routine to indicated processing of the
+ * buffer is complete.
+ * 4. When this routine is called, it will check if any threads are waiting
+ * to enqueue additional buffers and "wake them up" for further
+ * processing.
+ *
+ * Input parameters:
+ * handle - This is the handle that was provided to the lower-half
+ * start() method.
+ * apb - A pointer to the previsously enqueued ap_buffer_s
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * This function may be called from an interrupt handler.
+ *
+ ****************************************************************************/
+
+void audio_dequeuebuffer(FAR void *handle, FAR struct ap_buffer_s *apb)
+{
+ //FAR struct audio_upperhalf_s *upper = (FAR struct audio_upperhalf_s *)handle;
+
+ audllvdbg("Entry\n");
+
+ /* TODO: Implement the logic */
+
+}
+
+#endif /* CONFIG_AUDIO */
diff --git a/nuttx/audio/buffer.c b/nuttx/audio/buffer.c
new file mode 100644
index 000000000..d6c6ac930
--- /dev/null
+++ b/nuttx/audio/buffer.c
@@ -0,0 +1,165 @@
+/****************************************************************************
+ * audio/buffer.c
+ *
+ * Copyright (C) 2013 Ken Pettit. All rights reserved.
+ * Author: Ken Pettit <pettitkd@gmail.com>
+ *
+ * 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 <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <stdlib.h>
+#include <string.h>
+#include <assert.h>
+#include <semaphore.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/audio.h>
+#include <nuttx/usb/audio.h>
+
+#if defined(CONFIG_AUDIO)
+
+/****************************************************************************
+ * Preprocessor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: apb_semtake
+ *
+ * Take an Audio Pipeline Buffer.
+ *
+ ****************************************************************************/
+
+static void apb_semtake(sem_t *sem)
+{
+ /* Take the semaphore (perhaps waiting) */
+
+ while (sem_wait(sem) != 0)
+ {
+ /* The only case that an error should occr here is if
+ * the wait was awakened by a signal.
+ */
+
+ ASSERT(errno == EINTR);
+ }
+}
+
+/****************************************************************************
+ * Name: apb_semgive
+ ****************************************************************************/
+
+#define apb_semgive(s) sem_post(s)
+
+/****************************************************************************
+ * Name: apb_alloc
+ *
+ * Allocate an Audio Pipeline Buffer for use in the Audio sub-system. This
+ * will perform the actual allocate based on buffer data format, number of
+ * channels, etc. and prepare the buffer for consumption.
+ *
+ ****************************************************************************/
+
+FAR struct ap_buffer_s *apb_alloc(int type, int sampleCount)
+{
+ /* TODO: Implement the alloc logic */
+
+ return NULL;
+}
+
+/****************************************************************************
+ * Name: apb_prepare
+ *
+ * Prepare an AP Buffer for use in the Audio Pipeline.
+ *
+ ****************************************************************************/
+
+void apb_prepare(FAR struct ap_buffer_s *apb, int8_t allocmode, uint8_t format,
+ uint8_t subformat, apb_samp_t maxsamples)
+{
+ /* Perform a reference count decrement and possibly release the memory */
+
+}
+
+/****************************************************************************
+ * Name: apb_free
+ *
+ * Free's a previously allocated or referenced Audio Pipeline Buffer
+ *
+ ****************************************************************************/
+
+void apb_free(FAR struct ap_buffer_s *apb)
+{
+ /* Perform a reference count decrement and possibly release the memory */
+
+}
+
+/****************************************************************************
+ * Name: apb_reference
+ *
+ * Claim a reference to an Audio Pipeline Buffer. Each call to apb_reference
+ * will increment the reference count and must have a matching apb_free
+ * call. When the refcount decrements to zero, the buffer will be freed.
+ *
+ ****************************************************************************/
+
+void apb_reference(FAR struct ap_buffer_s *apb)
+{
+ /* TODO: Implement the reference logic */
+}
+
+#endif /* CONFIG_AUDIO */
+
diff --git a/nuttx/audio/pcm.c b/nuttx/audio/pcm.c
new file mode 100644
index 000000000..4f77c67c5
--- /dev/null
+++ b/nuttx/audio/pcm.c
@@ -0,0 +1,94 @@
+/****************************************************************************
+ * audio/pcm.c
+ *
+ * Copyright (C) 2013 Ken Pettit. All rights reserved.
+ * Author: Ken Pettit <pettitkd@gmail.com>
+ *
+ * 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 <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <stdlib.h>
+#include <string.h>
+#include <assert.h>
+#include <semaphore.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/audio.h>
+
+#if defined(CONFIG_AUDIO) && defined(CONFIG_AUDIO_FORMAT_PCM)
+
+/****************************************************************************
+ * Preprocessor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: audio_pcm_init
+ *
+ * Initialized the Audio PCM library.
+ *
+ ****************************************************************************/
+
+int audio_pcm_initialize(void)
+{
+ /* Initialze the Audio PCM routines */
+
+ return OK;
+}
+
+#endif /* CONFIG_AUDIO && CONFIG_AUDIO_FORMAT_PCM */
+
diff --git a/nuttx/configs/mikroe-stm32f4/src/up_nsh.c b/nuttx/configs/mikroe-stm32f4/src/up_nsh.c
index 9fcf160f9..648f69c64 100644
--- a/nuttx/configs/mikroe-stm32f4/src/up_nsh.c
+++ b/nuttx/configs/mikroe-stm32f4/src/up_nsh.c
@@ -63,6 +63,10 @@
# include "stm32_usbhost.h"
#endif
+#ifdef CONFIG_AUDIO
+# include "nuttx/audio.h"
+#endif
+
#include "stm32.h"
#include "mikroe-stm32f4-internal.h"
@@ -178,6 +182,9 @@ int nsh_archinitialize(void)
FAR struct spi_dev_s *spi;
FAR struct mtd_dev_s *mtd;
#endif
+#ifdef CONFIG_AUDIO
+ FAR struct audio_lowerhalf_s *pVs1053;
+#endif
int ret;
/* Configure SPI-based devices */
@@ -344,5 +351,21 @@ int nsh_archinitialize(void)
#endif
+ /* Configure the Audio sub-system if enabled */
+
+#ifdef CONFIG_AUDIO
+ pVs1053 = vs1053_initialize(0);
+ if (pVs1053 == NULL)
+ {
+ message("nsh_archinitialize: Failed to initialize VS1053 Audio module\n");
+ }
+ else
+ {
+ /* Bind the vs1053 to the audio upper-half driver */
+
+ audio_register("mp30", pVs1053);
+ }
+
+#endif /* CONFIG_AUDIO */
return OK;
}
diff --git a/nuttx/drivers/Kconfig b/nuttx/drivers/Kconfig
index f3d2c871a..efcf9bc55 100644
--- a/nuttx/drivers/Kconfig
+++ b/nuttx/drivers/Kconfig
@@ -257,6 +257,19 @@ if ANALOG
source drivers/analog/Kconfig
endif
+menuconfig AUDIO_DEVICES
+ bool "Audio Device Support"
+ default n
+ ---help---
+ This directory holds implementations of audio device drivers.
+ This includes drivers for MP3, WMA and Ogg Vorbis encoding,
+ decoding, as well as drivers for interfacing with external
+ DSP chips to perform custom audio functions.
+
+if AUDIO_DEVICES
+source drivers/audio/Kconfig
+endif
+
menuconfig BCH
bool "Block-to-Character (BCH) Support"
default n
diff --git a/nuttx/drivers/Makefile b/nuttx/drivers/Makefile
index aaaa67bd7..c91870ec9 100644
--- a/nuttx/drivers/Makefile
+++ b/nuttx/drivers/Makefile
@@ -50,6 +50,7 @@ VPATH = .
# the appropriate paths to the VPATH variable
include analog$(DELIM)Make.defs
+include audio$(DELIM)Make.defs
include bch$(DELIM)Make.defs
include input$(DELIM)Make.defs
include lcd$(DELIM)Make.defs
diff --git a/nuttx/drivers/audio/Kconfig b/nuttx/drivers/audio/Kconfig
new file mode 100644
index 000000000..752bce1ae
--- /dev/null
+++ b/nuttx/drivers/audio/Kconfig
@@ -0,0 +1,14 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
+
+config VS1053
+ bool "VS1053 codec chip"
+ default n
+ ---help---
+ Select to enable support for the VS1053 Audio codec by VLSI Solutions.
+ This chip provides encoding and decoding of MP3, WMA, AAC and Ogg
+ Vorbis format audio. It also has a general DSP which is user
+ programmable to perform special audio (or any DSP) functions.
+
diff --git a/nuttx/drivers/audio/Make.defs b/nuttx/drivers/audio/Make.defs
new file mode 100644
index 000000000..353be5844
--- /dev/null
+++ b/nuttx/drivers/audio/Make.defs
@@ -0,0 +1,51 @@
+############################################################################
+# drivers/audio/Make.defs
+# These drivers support various Audio devices using the NuttX Audio
+# interface.
+#
+# Copyright (C) 2013 Ken Pettit. All rights reserved.
+# Author: Ken Pettit <pettitkd@gmail.com>
+#
+# 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.
+#
+############################################################################
+
+# Include Audio drivers
+
+ifeq ($(CONFIG_AUDIO),y)
+
+ifeq ($(CONFIG_VS1053),y)
+CSRCS += vs1053.c
+endif
+
+# Include Audio driver support
+
+DEPPATH += --dep-path audio
+VPATH += :audio
+
+endif
diff --git a/nuttx/drivers/audio/vs1053.c b/nuttx/drivers/audio/vs1053.c
new file mode 100644
index 000000000..6f143acf9
--- /dev/null
+++ b/nuttx/drivers/audio/vs1053.c
@@ -0,0 +1,257 @@
+/****************************************************************************
+ * drivers/audio/vs1053.c
+ *
+ * Audio device driver for VLSI Solutions VS1053 Audio codec.
+ *
+ * Copyright (C) 2013 Ken Pettit. All rights reserved.
+ * Author: Ken Pettit <pettitkd@gmail.com>
+ *
+ * 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 <sys/types.h>
+#include <sys/ioctl.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <stddef.h>
+#include <string.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/fs/fs.h>
+#include <nuttx/fs/ioctl.h>
+#include <nuttx/audio.h>
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct vs1053_struct_s
+{
+ FAR struct audio_lowerhalf_s lower; /* We derive the Audio lower half */
+
+ /* Our specific driver data goes here */
+ int spidevice; /* Placeholder device data */
+
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static int vs1053_getcaps(FAR struct audio_lowerhalf_s *lower, int type,
+ FAR struct audio_caps_s *pCaps);
+static int vs1053_configure(FAR struct audio_lowerhalf_s *lower,
+ FAR const struct audio_caps_s *pCaps);
+static int vs1053_shutdown(FAR struct audio_lowerhalf_s *lower);
+static int vs1053_start(FAR struct audio_lowerhalf_s *lower);
+static int vs1053_stop(FAR struct audio_lowerhalf_s *lower);
+static int vs1053_enqueuebuffer(FAR struct audio_lowerhalf_s *lower,
+ FAR struct ap_buffer_s *apb);
+static int vs1053_ioctl(FAR struct audio_lowerhalf_s *lower, int cmd,
+ unsigned long arg);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static const struct audio_ops_s g_audioops =
+{
+ vs1053_getcaps, /* getcaps */
+ vs1053_configure, /* configure */
+ vs1053_shutdown, /* shutdown */
+ vs1053_start, /* start */
+ vs1053_stop, /* stop */
+ vs1053_enqueuebuffer, /* enqueue_buffer */
+ vs1053_ioctl /* ioctl */
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: vs1053_getcaps
+ *
+ * Description: Get the audio device capabilities
+ *
+ ****************************************************************************/
+
+static int vs1053_getcaps(FAR struct audio_lowerhalf_s *lower, int type,
+ FAR struct audio_caps_s *pCaps)
+{
+ audvdbg("Entry\n");
+ return OK;
+}
+
+/****************************************************************************
+ * Name: vs1053_configure
+ *
+ * Description: Configure the audio device for the specified mode of
+ * operation.
+ *
+ ****************************************************************************/
+
+static int vs1053_configure(FAR struct audio_lowerhalf_s *lower,
+ FAR const struct audio_caps_s *pCaps)
+{
+ audvdbg("Entry\n");
+ return OK;
+}
+
+/****************************************************************************
+ * Name: vs1053_shutdown
+ *
+ * Description: Shutdown the VS1053 chip and put it in the lowest power
+ * state possible.
+ *
+ ****************************************************************************/
+
+static int vs1053_shutdown(FAR struct audio_lowerhalf_s *lower)
+{
+ audvdbg("Entry\n");
+ return OK;
+}
+
+/****************************************************************************
+ * Name: vs1053_start
+ *
+ * Description: Start the configured operation (audio streaming, volume
+ * enabled, etc.).
+ *
+ ****************************************************************************/
+
+static int vs1053_start(FAR struct audio_lowerhalf_s *lower)
+{
+ //struct vs1053_struct_s *dev = (struct vs1053_struct_s *) lower;
+
+ /* Perform the start */
+
+ return OK;
+}
+
+/****************************************************************************
+ * Name: vs1053_stop
+ *
+ * Description: Stop the configured operation (audio streaming, volume
+ * disabled, etc.).
+ *
+ ****************************************************************************/
+
+static int vs1053_stop(FAR struct audio_lowerhalf_s *lower)
+{
+ /* Stop all audio streaming */
+
+ return OK;
+}
+
+/****************************************************************************
+ * Name: vs1053_enqueuebuffer
+ *
+ * Description: Enqueue an Audio Pipeline Buffer for playback/ processing.
+ *
+ ****************************************************************************/
+
+static int vs1053_enqueuebuffer(FAR struct audio_lowerhalf_s *lower,
+ FAR struct ap_buffer_s *apb )
+{
+ return OK;
+}
+
+/****************************************************************************
+ * Name: vs1053_ioctl
+ *
+ * Description: Perform a device ioctl
+ *
+ ****************************************************************************/
+
+static int vs1053_ioctl(FAR struct audio_lowerhalf_s *lower, int cmd,
+ unsigned long arg)
+{
+ return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: vs1053_initialize
+ *
+ * Description:
+ * Initialize the VS1053 device
+ *
+ * Input Parameters:
+ * spidevice - This is a placeholder argument until the Audio interface
+ * has been flushed out a bit.
+ *
+ ****************************************************************************/
+
+struct audio_lowerhalf_s *vs1053_initialize(int spidevice)
+{
+ struct vs1053_struct_s *dev;
+
+ /* Sanity check */
+
+#ifdef CONFIG_DEBUG
+ if (spidevice < 0 || spidevice > 3)
+ {
+ return NULL;
+ }
+#endif
+
+ /* Allocate a VS1053 device structure */
+
+ dev = (struct vs1053_struct_s *)kmalloc(sizeof(struct vs1053_struct_s));
+ if (dev)
+ {
+ /* Initialize the SMART device structure */
+
+ dev->lower.ops = &g_audioops;
+
+ /* Save our specific device data */
+
+ dev->spidevice = spidevice;
+ }
+
+ return &dev->lower;
+}
diff --git a/nuttx/include/debug.h b/nuttx/include/debug.h
index 70ae2ee18..97b7ed798 100644
--- a/nuttx/include/debug.h
+++ b/nuttx/include/debug.h
@@ -284,6 +284,18 @@
# define lllvdbg(x...)
#endif
+#ifdef CONFIG_DEBUG_AUDIO
+# define auddbg(format, arg...) dbg(format, ##arg)
+# define audlldbg(format, arg...) lldbg(format, ##arg)
+# define audvdbg(format, arg...) vdbg(format, ##arg)
+# define audllvdbg(format, arg...) llvdbg(format, ##arg)
+#else
+# define auddbg(x...)
+# define audlldbg(x...)
+# define audvdbg(x...)
+# define audllvdbg(x...)
+#endif
+
#else /* CONFIG_CPP_HAVE_VARARGS */
/* Variable argument macros NOT supported */
@@ -453,6 +465,18 @@
# define lllvdbg (void)
#endif
+#ifdef CONFIG_DEBUG_AUDIO
+# define auddbg dbg
+# define audlldbg lldbg
+# define audvdbg vdbg
+# define audllvdbg llvdbg
+#else
+# define auddbg (void)
+# define audlldbg (void)
+# define audvdbg (void)
+# define audllvdbg (void)
+#endif
+
#endif /* CONFIG_CPP_HAVE_VARARGS */
/* Buffer dumping macros do not depend on varargs */
@@ -559,6 +583,14 @@
# define lvdbgdumpbuffer(m,b,n)
#endif
+#ifdef CONFIG_DEBUG_AUDIO
+# define auddbgdumpbuffer(m,b,n) dbgdumpbuffer(m,b,n)
+# define audvdbgdumpbuffer(m,b,n) vdbgdumpbuffer(m,b,n)
+#else
+# define auddbgdumpbuffer(m,b,n)
+# define audvdbgdumpbuffer(m,b,n)
+#endif
+
/****************************************************************************
* Public Type Declarations
****************************************************************************/
diff --git a/nuttx/include/nuttx/audio.h b/nuttx/include/nuttx/audio.h
new file mode 100644
index 000000000..1e6464adc
--- /dev/null
+++ b/nuttx/include/nuttx/audio.h
@@ -0,0 +1,462 @@
+/****************************************************************************
+ * include/nuttx/audio.h
+ *
+ * Copyright (C) 2013 Ken Pettit. All rights reserved.
+ * Author: Ken Pettit <pettitkd@gmail.com>
+ *
+ * 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 __INCLUDE_NUTTX_AUDIO_H
+#define __INCLUDE_NUTTX_AUDIO_H
+
+/* For the purposes of this driver, an Audio device is any device that
+ * generates, records, mixes, or otherwise modifies audio data in any format,
+ * such as PCM, MP3, AAC, etc.
+ *
+ * The Audio driver is split into two parts:
+ *
+ * 1) An "upper half", generic driver that provides the comman Audio interface
+ * to application level code, and
+ * 2) A "lower half", platform-specific driver that implements the low-level
+ * controls to configure and communicate with the audio device(s).
+ */
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+
+#include <nuttx/fs/ioctl.h>
+
+#ifdef CONFIG_AUDIO
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+/* CONFIG_AUDIO - Enables Audio driver support
+ * CONFIG_DEBUG_AUDIO - If enabled (with CONFIG_DEBUG and, optionally,
+ * CONFIG_DEBUG_VERBOSE), this will generate output that can be used to
+ * debug Audio drivers.
+ */
+
+/* IOCTL Commands ***********************************************************/
+/* The Audio module uses a standard character driver framework. However, a
+ * lot of the Audio driver functionality is configured via a device control
+ * interface, such as sampling rate, volume, data format, etc.
+ * The Audio ioctl commands are lised below:
+ *
+ * AUDIOIOC_GETCAPS - Get the Audio Device Capabilities
+ *
+ * ioctl argument: Pointer to the audio_caps_s structure to receive the
+ * capabilities info. The "len" and "type" fields should
+ * be filled in prior to calling this ioctl. To get
+ * overall capabilities, specify the type as
+ * AUDIO_TYPE_QUERY, otherwise specify any type that was
+ * reported by the device during the QUERY.
+ *
+ * AUDIOIOC_CONFIGURE - Configure device for the specified mode
+ *
+ * ioctl argument: Pointer to the audio_caps_s structure which identifies
+ * the capabilities to configure for.
+ *
+ * AUDIOIOC_SHUTDOWN - Shutdown the device.
+ *
+ * ioctl argument: None
+ *
+ * AUDIOIOC_START - Start Audio streaming
+ *
+ * ioctl argument: None
+ *
+ * AUDIOIOC_STOP - Stop Audio streaming
+ *
+ * ioctl argument: None
+ */
+
+#define AUDIOIOC_GETCAPS _AUDIOIOC(1)
+#define AUDIOIOC_CONFIGURE _AUDIOIOC(2)
+#define AUDIOIOC_SHUTDOWN _AUDIOIOC(3)
+#define AUDIOIOC_START _AUDIOIOC(4)
+#define AUDIOIOC_STOP _AUDIOIOC(5)
+
+/* Audio Device Types *******************************************************/
+/* The NuttX audio interface support different types of audio devices for
+ * input, output, synthesis, and manupulation of audio data. A given driver/
+ * device could support a combination of these device type. The following
+ * is a list of bit-field definitons for defining the device type.
+ */
+
+#define AUDIO_TYPE_QUERY 0x0000
+#define AUDIO_TYPE_INPUT 0x0002
+#define AUDIO_TYPE_OUTPUT 0x0004
+#define AUDIO_TYPE_MIXER 0x0008
+#define AUDIO_TYPE_SELECTOR 0x0010
+#define AUDIO_TYPE_FEATURE 0x0020
+#define AUDIO_TYPE_EFFECT 0x0040
+#define AUDIO_TYPE_PROCESSING 0x0080
+#define AUDIO_TYPE_EXTENSION 0x0100
+
+/* Audio Format Types *******************************************************/
+/* The following defines the audio data format types in NuttX. */
+
+#define AUDIO_FMT_UNDEF 0x00
+#define AUDIO_FMT_OTHER 0x01
+#define AUDIO_FMT_MPEG 0x02
+#define AUDIO_FMT_AC3 0x03
+#define AUDIO_FMT_WMA 0x04
+#define AUDIO_FMT_DTS 0x05
+#define AUDIO_FMT_PCM 0x06
+#define AUDIO_FMT_MP3 0x07
+#define AUDIO_FMT_MIDI 0x08
+#define AUDIO_FMT_OGG_VORBIS 0x09
+
+/* Audio Sub-Format Types ***************************************************/
+
+#define AUDIO_SUBFMT_PCM_MP1 0x01
+#define AUDIO_SUBFMT_PCM_MP2 0x02
+#define AUDIO_SUBFMT_PCM_MP3 0x03
+#define AUDIO_SUBFMT_PCM_MU_LAW 0x04
+#define AUDIO_SUBFMT_PCM_A_LAW 0x05
+#define AUDIO_SUBFMT_PCM_U8 0x06
+#define AUDIO_SUBFMT_PCM_S8 0x07
+#define AUDIO_SUBFMT_PCM_U16_LE 0x08
+#define AUDIO_SUBFMT_PCM_S16_BE 0x09
+#define AUDIO_SUBFMT_PCM_S16_LE 0x0A
+#define AUDIO_SUBFMT_PCM_U16_BE 0x0B
+
+/* Supported Sampling Rates *************************************************/
+
+#define AUDIO_RATE_22K 0x01
+#define AUDIO_RATE_44K 0x02
+#define AUDIO_RATE_48K 0x03
+#define AUDIO_RATE_96K 0x04
+#define AUDIO_RATE_128K 0x05
+#define AUDIO_RATE_160K 0x06
+#define AUDIO_RATE_172K 0x07
+#define AUDIO_RATE_192K 0x08
+#define AUDIO_RATE_320K 0x09
+
+/* Audio Pipeline Buffer (AP Buffer) flags **********************************/
+
+#define AUDIO_ABP_ALIGNMENT 0x000F /* Mask to define buffer alignment */
+#define AUDIO_ABP_CANDMA 0x0010 /* Set if the data is DMA'able */
+#define AUDIO_ABP_STATIC 0x0020 /* Set if statically allocated */
+#define AUDIO_ABP_ACTIVE 0x0040 /* Set if this buffer is still active.
+ * A buffer could become inactive
+ * if it is processed by an output
+ * device or a processing device
+ * that replaces it with an alternate
+ * buffer as a result of some DSP
+ * operation, etc.
+ */
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/* Define the size of AP Buffer sample count base on CONFIG */
+
+#ifdef CONFIG_AUDIO_LARGE_BUFFERS
+typedef uint32_t apb_samp_t;
+#else
+typedef uint16_t apb_samp_t;
+#endif
+
+/* This structure is used to describe the audio device capabilities */
+
+struct audio_caps_s
+{
+ uint8_t ac_len; /* Length of the structure */
+ uint8_t ac_type; /* Capabilities (device) type */
+ uint8_t ac_subtype; /* Capabilities sub-type, if needed */
+ uint8_t ac_channels; /* Number of channels (1, 2, 5, 7) */
+ uint8_t ac_format[2]; /* Audio data format(s) for this device */
+ uint8_t ac_controls[4]; /* Device specific controls. For AUDIO_DEVICE_QUERY,
+ * this field reports the device type supported
+ * by this lower-half driver. */
+};
+
+/* This structure describes the characteristics of the Audio samples */
+
+struct audio_info_s
+{
+ uint8_t samplerate; /* Sample Rate of the audio data */
+ uint8_t channels; /* Number of channels (1, 2, 5, 7) */
+ uint8_t format; /* Audio data format */
+ uint8_t subformat; /* Audio subformat (maybe should be combined with format? */
+};
+
+/* This structure describes an Audio Pipeline Buffer */
+
+struct ap_buffer_s
+{
+ struct audio_info_s i; /* The info for samples in this buffer */
+ apb_samp_t nmaxsamples;/* The maximum number of samples */
+ apb_samp_t nsamples; /* The number of samples used */
+ uint16_t flags; /* Buffer flags */
+ uint8_t samp[0]; /* Offset of the first sample */
+} packed_struct;
+
+/* This structure is a set a callback functions used to call from the upper-
+ * half, generic Audo driver into lower-half, platform-specific logic that
+ * supports the low-level functionality.
+ */
+
+struct audio_lowerhalf_s;
+struct audio_ops_s
+{
+ /* This method is called to retrieve the lower-half device capabilities.
+ * It will be called with device type AUDIO_TYPE_QUERY to request the
+ * overall capabilities, such as to determine the types of devices supported
+ * audio formats supported, etc. Then it may be called once or more with
+ * reported supported device types to determine the specific capabilities
+ * of that device type (such as MP3 encoder, WMA encoder, PCM output, etc.).
+ */
+
+ CODE int (*getcaps)(FAR struct audio_lowerhalf_s *dev, int type,
+ FAR struct audio_caps_s *pCaps);
+
+ /* This method is called to configure the driver for a specific mode of
+ * operation defined by the parameters selected in supplied device caps
+ * strucure. The lower-level device should perform any initialization
+ * needed to prepare for operations in the specified mode. It should not,
+ * however, process any audio data until the start method is called.
+ */
+
+ CODE int (*configure)(FAR struct audio_lowerhalf_s *dev,
+ FAR const struct audio_caps_s *pCaps);
+
+ /* This method is called when the driver is closed. The lower half driver
+ * should stop processing audio data, including terminating any active
+ * output generation. It should also disable the audio hardware and put
+ * it into the lowest possible power usage state.
+ *
+ * Any enqueued Audio Pipeline Buffers that have not been processed / dequeued
+ * should be dequeued by this function.
+ */
+
+ CODE int (*shutdown)(FAR struct audio_lowerhalf_s *dev);
+
+ /* Start audio streaming in the configured mode. For input and synthesis
+ * devices, this means it should begin sending streaming audio data. For output
+ * or processing type device, it means it should begin processing of any enqueued
+ * Audio Pipline Buffers.
+ */
+
+ CODE int (*start)(FAR struct audio_lowerhalf_s *dev);
+
+ /* Stop audio streaming and/or processing of enqueued Audio Pipeline Buffers */
+
+ CODE int (*stop)(FAR struct audio_lowerhalf_s *dev);
+
+ /* Enqueue a buffer for processing. This is a non-blocking enqueue operation.
+ * If the lower-half driver's buffer queue is full, then it should return an
+ * error code of -ENOMEM, and the upper-half driver can decide to either block
+ * the calling thread or deal with it in a non-blocking manner.
+
+ * For each call to enqueuebuffer, the lower-half driver must call
+ * audio_dequeuebuffer when it is finished processing the bufferr, passing the
+ * previously enqueued apb and a dequeue status so that the upper-half driver
+ * can decide if a waiting thread needs to be release, if the dequeued buffer
+ * should be passed to the next block in the Audio Pipeline, etc.
+ */
+
+ CODE int (*enqueuebuffer)(FAR struct audio_lowerhalf_s *dev,
+ FAR struct ap_buffer_s *apb);
+
+ /* Lower-half logic may support platform-specific ioctl commands */
+
+ CODE int (*ioctl)(FAR struct audio_lowerhalf_s *dev,
+ int cmd, unsigned long arg);
+};
+
+/* This structure is the generic form of state structure used by lower half
+ * Audio driver. This state structure is passed to the Audio driver when the
+ * driver is initialized. Then, on subsequent callbacks into the lower half
+ * Audio logic, this structure is provided so that the Audio logic can
+ * maintain state information.
+ *
+ * Normally that Audio logic will have its own, custom state structure
+ * that is simply cast to struct audio_lowerhalf_s. In order to perform such
+ * casts, the initial fields of the custom state structure match the initial
+ * fields of the following generic Audio state structure.
+ */
+
+struct audio_lowerhalf_s
+{
+ /* The first field of this state structure must be a pointer to the Audio
+ * callback structure:
+ */
+
+ FAR const struct audio_ops_s *ops;
+
+ /* The custom Audio device state structure may include additional fields
+ * after the pointer to the Audio callback structure.
+ */
+};
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * "Upper-Half" Audio Driver Interfaces
+ ****************************************************************************/
+/****************************************************************************
+ * Name: audio_register
+ *
+ * Description:
+ * This function binds an instance of a "lower half" Audio driver with the
+ * "upper half" Audio device and registers that device so that can be used
+ * by application code.
+ *
+ * When this function is called, the "lower half" driver should be in the
+ * reset state (as if the shutdown() method had already been called).
+ *
+ * Input parameters:
+ * name - The name of the audio device. This name will be used to generate
+ * a full path to the driver in the format "/dev/audio/[name]" in the NuttX
+ * filesystem (i.e. the path "/dev/audio" will be prepended to the supplied
+ * device name. The recommended convention is to name Audio drivers
+ * based on the type of functionality they provide, such as "/dev/audio/pcm0",
+ * "/dev/audio/midi0", "/dev/audio/mp30, etc.
+ * dev - A pointer to an instance of lower half audio driver. This instance
+ * is bound to the Audio driver and must persists as long as the driver
+ * persists.
+ *
+ * Returned Value:
+ * Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+EXTERN int audio_register(FAR const char *name, FAR struct audio_lowerhalf_s *dev);
+
+/****************************************************************************
+ * Name: abp_alloc
+ *
+ * Description:
+ * Allocated an AP Buffer and prepares it for use. This allocates a dynamically
+ * allocated buffer that has no special DMA capabilities. If a static buffer
+ * or a buffer with DMA ability is needed, then it must be allocated manually
+ * and then call apb_prepare, passing it the allocated memory.
+ *
+ * Input parameters:
+ *
+ * Returned Value:
+ * Pointer to the allocated buffer or NULL if no memory.
+ *
+ ****************************************************************************/
+
+FAR struct ap_buffer_s *apb_alloc(int type, int sampleCount);
+
+/****************************************************************************
+ * Name: abp_prepare
+ *
+ * Description:
+ * Prepare a pre-allocated AP Buffer for use in the Audio Pipeline.
+ *
+ * Input parameters:
+ * apb - The pre-allocated AP Buffer
+ * size - The size of the pre-allocated buffer (for verification)
+ * allocmode - Indicates if the buffer is static or dynamic memory
+ * format - The format of samples to be used in the buffer
+ * subformat - The sub-format of samples
+ * maxsamples - The size, in samples, of the buffer
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+EXTERN void apb_prepare(struct ap_buffer_s *apb, int8_t allocmode, uint8_t format,
+ uint8_t subformat, apb_samp_t maxsamples);
+
+/****************************************************************************
+ * Name: apb_free
+ *
+ * Free's a previously allocated or referenced Audio Pipeline Buffer
+ *
+ ****************************************************************************/
+
+EXTERN void apb_free(FAR struct ap_buffer_s *apb);
+
+/****************************************************************************
+ * Name: apb_reference
+ *
+ * Claim a reference to an Audio Pipeline Buffer. Each call to apb_reference
+ * will increment the reference count and must have a matching apb_free
+ * call. When the refcount decrements to zero, the buffer will be freed.
+ *
+ ****************************************************************************/
+
+EXTERN void apb_reference(FAR struct ap_buffer_s *apb);
+
+/****************************************************************************
+ * Platform-Dependent "Lower-Half" Audio Driver Interfaces
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: vs1053_initialize
+ *
+ * Description:
+ * This function initializes the driver for the VS1053 codec chip
+ *
+ * Input parameters:
+ * spi - This is a placeholder for now. Actual init parameters will be
+ * determined once the audio interface is "finalized".
+ *
+ * Returned Value:
+ * Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+#ifdef CONFIG_VS1053
+EXTERN FAR struct audio_lowerhalf_s *vs1053_initialize(int spidevice);
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* CONFIG_AUDIO */
+#endif /* __INCLUDE_NUTTX_AUDIO_H */
diff --git a/nuttx/include/nuttx/fs/ioctl.h b/nuttx/include/nuttx/fs/ioctl.h
index bd80a7150..1e44729af 100644
--- a/nuttx/include/nuttx/fs/ioctl.h
+++ b/nuttx/include/nuttx/fs/ioctl.h
@@ -66,6 +66,7 @@
#define _CAIOCBASE (0x0d00) /* CDC/ACM ioctl commands */
#define _BATIOCBASE (0x0e00) /* Battery driver ioctl commands */
#define _QEIOCBASE (0x0f00) /* Quadrature encoder ioctl commands */
+#define _AUDIOIOCBASE (0x1000) /* Audio ioctl commands */
/* Macros used to manage ioctl commands */
@@ -232,6 +233,12 @@
#define _QEIOCVALID(c) (_IOC_TYPE(c)==_QEIOCBASE)
#define _QEIOC(nr) _IOC(_QEIOCBASE,nr)
+/* NuttX Audio driver ioctol definitions ***********************/
+/* (see nuttx/audio/audio.h) */
+
+#define _AUDIOIOCVALID(c) (_IOC_TYPE(c)==_AUDIOIOCBASE)
+#define _AUDIOIOC(nr) _IOC(_AUDIOIOCBASE,nr)
+
/****************************************************************************
* Public Type Definitions
****************************************************************************/