summaryrefslogtreecommitdiff
path: root/nuttx/include
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-10-27 07:44:53 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-10-27 07:44:53 -0600
commit66bc3094e689ff4a96c9ac2755335d45b8765aa1 (patch)
treea25e3cf4f1a61bcd727587fefc2725316c82ee05 /nuttx/include
parent6dc974b4b0d8423cc9073e425a2e3a4370160df6 (diff)
downloadpx4-nuttx-66bc3094e689ff4a96c9ac2755335d45b8765aa1.tar.gz
px4-nuttx-66bc3094e689ff4a96c9ac2755335d45b8765aa1.tar.bz2
px4-nuttx-66bc3094e689ff4a96c9ac2755335d45b8765aa1.zip
Updated audio subsystem from Ken Pettit
Diffstat (limited to 'nuttx/include')
-rw-r--r--nuttx/include/nuttx/audio/audio.h376
1 files changed, 316 insertions, 60 deletions
diff --git a/nuttx/include/nuttx/audio/audio.h b/nuttx/include/nuttx/audio/audio.h
index 6234ac0db..be03cc71e 100644
--- a/nuttx/include/nuttx/audio/audio.h
+++ b/nuttx/include/nuttx/audio/audio.h
@@ -36,10 +36,10 @@
#ifndef __INCLUDE_NUTTX_AUDIO_AUDIO_H
#define __INCLUDE_NUTTX_AUDIO_AUDIO_H
-/* For the purposes of this driver, an Audio device is any device that
+/* 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
@@ -57,6 +57,8 @@
#include <nuttx/fs/ioctl.h>
#include <nuttx/spi/spi.h>
+#include <queue.h>
+#include <semaphore.h>
#ifdef CONFIG_AUDIO
@@ -69,10 +71,10 @@
* 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
+ * 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:
*
@@ -81,7 +83,7 @@
* 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
+ * overall capabilities, specify the type as
* AUDIO_TYPE_QUERY, otherwise specify any type that was
* reported by the device during the QUERY.
*
@@ -104,10 +106,21 @@
*/
#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)
+#define AUDIOIOC_RESERVE _AUDIOIOC(2)
+#define AUDIOIOC_RELEASE _AUDIOIOC(3)
+#define AUDIOIOC_CONFIGURE _AUDIOIOC(4)
+#define AUDIOIOC_SHUTDOWN _AUDIOIOC(5)
+#define AUDIOIOC_START _AUDIOIOC(6)
+#define AUDIOIOC_STOP _AUDIOIOC(7)
+#define AUDIOIOC_PAUSE _AUDIOIOC(8)
+#define AUDIOIOC_RESUME _AUDIOIOC(9)
+#define AUDIOIOC_GETBUFFERINFO _AUDIOIOC(10)
+#define AUDIOIOC_ALLOCBUFFER _AUDIOIOC(11)
+#define AUDIOIOC_FREEBUFFER _AUDIOIOC(12)
+#define AUDIOIOC_ENQUEUEBUFFER _AUDIOIOC(13)
+#define AUDIOIOC_REGISTERMQ _AUDIOIOC(14)
+#define AUDIOIOC_UNREGISTERMQ _AUDIOIOC(15)
+#define AUDIOIOC_HWRESET _AUDIOIOC(16)
/* Audio Device Types *******************************************************/
/* The NuttX audio interface support different types of audio devices for
@@ -129,16 +142,17 @@
/* 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
+#define AUDIO_FMT_UNDEF 0x000
+#define AUDIO_FMT_OTHER 0x001
+#define AUDIO_FMT_MPEG 0x002
+#define AUDIO_FMT_AC3 0x004
+#define AUDIO_FMT_WMA 0x008
+#define AUDIO_FMT_DTS 0x010
+#define AUDIO_FMT_PCM 0x020
+#define AUDIO_FMT_WAV 0x020
+#define AUDIO_FMT_MP3 0x040
+#define AUDIO_FMT_MIDI 0x080
+#define AUDIO_FMT_OGG_VORBIS 0x100
/* Audio Sub-Format Types ***************************************************/
@@ -156,21 +170,72 @@
/* 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
+#define AUDIO_SAMP_RATE_8K 0x0001
+#define AUDIO_SAMP_RATE_11K 0x0002
+#define AUDIO_SAMP_RATE_16K 0x0004
+#define AUDIO_SAMP_RATE_22K 0x0008
+#define AUDIO_SAMP_RATE_32K 0x0010
+#define AUDIO_SAMP_RATE_44K 0x0020
+#define AUDIO_SAMP_RATE_48K 0x0040
+#define AUDIO_SAMP_RATE_96K 0x0080
+#define AUDIO_SAMP_RATE_128K 0x0100
+#define AUDIO_SAMP_RATE_160K 0x0200
+#define AUDIO_SAMP_RATE_172K 0x0400
+#define AUDIO_SAMP_RATE_192K 0x0800
+
+/* Supported Bit Rates *************************************************/
+
+#define AUDIO_BIT_RATE_22K 0x01
+#define AUDIO_BIT_RATE_44K 0x02
+#define AUDIO_BIT_RATE_48K 0x04
+#define AUDIO_BIT_RATE_96K 0x08
+#define AUDIO_BIT_RATE_128K 0x10
+#define AUDIO_BIT_RATE_160K 0x20
+#define AUDIO_BIT_RATE_172K 0x40
+#define AUDIO_BIT_RATE_192K 0x80
+
+/* Supported Feature Units controls *****************************************/
+
+#define AUDIO_FU_UNDEF 0x0000
+#define AUDIO_FU_MUTE 0x0001
+#define AUDIO_FU_VOLUME 0x0002
+#define AUDIO_FU_BASS 0x0004
+#define AUDIO_FU_MID 0x0008
+#define AUDIO_FU_TREBLE 0x0010
+#define AUDIO_FU_EQUALIZER 0x0020
+#define AUDIO_FU_AGC 0x0040
+#define AUDIO_FU_DELAY 0x0080
+#define AUDIO_FU_BASS_BOOST 0x0100
+#define AUDIO_FU_LOUDNESS 0x0200
+#define AUDIO_FU_INP_GAIN 0x0400
+#define AUDIO_FU_BALANCE 0x0800
+#define AUDIO_FU_PHASE_INVERT 0x1000
+#define AUDIO_FU_UNDERFLOW 0x2000
+#define AUDIO_FU_OVERFLOW 0x4000
+#define AUDIO_FU_LATENCY 0x8000
+
+/* Processing Unit controls *************************************************/
+
+#define AUDIO_PU_UNDEF 0x00
+#define AUDIO_PU_UPDOWNMIX 0x01
+#define AUDIO_PU_DOLBY_PROLOGIC 0x02
+#define AUDIO_PU_STEREO_EXTENDER 0x03
+
+/* Stereo Extender PU Controls **********************************************/
+
+#define AUDIO_STEXT_UNDEF 0x00
+#define AUDIO_STEXT_ENABLE 0x01
+#define AUDIO_STEXT_WIDTH 0x02
+#define AUDIO_STEXT_UNDERFLOW 0x03
+#define AUDIO_STEXT_OVERFLOW 0x04
+#define AUDIO_STEXT_LATENCY 0x05
/* Audio Callback Reasons ***************************************************/
#define AUDIO_CALLBACK_UNDEF 0x00
#define AUDIO_CALLBACK_DEQUEUE 0x01
#define AUDIO_CALLBACK_IOERR 0x02
+#define AUDIO_CALLBACK_COMPLETE 0x03
/* Audio Pipeline Buffer (AP Buffer) flags **********************************/
@@ -186,6 +251,25 @@
* operation, etc.
*/
+/* Standard Audio Message Queue message IDs */
+
+#define AUDIO_MSG_NONE 0
+#define AUDIO_MSG_DEQUEUE 1
+#define AUDIO_MSG_START 2
+#define AUDIO_MSG_STOP 3
+#define AUDIO_MSG_PAUSE 4
+#define AUDIO_MSG_RESUME 5
+#define AUDIO_MSG_DATA_REQUEST 6
+#define AUDIO_MSG_ENQUEUE 7
+#define AUDIO_MSG_COMPLETE 8
+#define AUDIO_MSG_USER 64
+
+/* Audio Pipeline Buffer flags */
+
+#define AUDIO_APB_OUTPUT_ENQUEUED 0x0001;
+#define AUDIO_APB_OUTPUT_PROCESS 0x0002;
+#define AUDIO_APB_DEQUEUED 0x0004;
+
/****************************************************************************
* Public Types
****************************************************************************/
@@ -212,6 +296,14 @@ struct audio_caps_s
* by this lower-half driver. */
};
+struct audio_caps_desc_s
+{
+#ifdef CONFIG_AUDIO_MULTI_SESSION
+ FAR void *session; /* Associated session */
+#endif
+ struct audio_caps_s caps; /* The capabilities struct */
+};
+
/* This structure describes the characteristics of the Audio samples */
struct audio_info_s
@@ -222,21 +314,99 @@ struct audio_info_s
uint8_t subformat; /* Audio subformat (maybe should be combined with format? */
};
+/* This structure describes the preferred number and size of
+ * audio pipeline buffers for the audio device. Each device
+ * may have unique needs regarding size and qty of buffers,
+ * so this info is queried from the lower-half driver.
+ */
+
+#ifdef CONFIG_AUDIO_DRIVER_SPECIFIC_BUFFERS
+struct ap_buffer_info_s
+{
+ apb_samp_t nbuffers; /* Preferred qty of buffers */
+ apb_samp_t buffer_size; /* Preferred size of the buffers */
+};
+#endif
+
/* This structure describes an Audio Pipeline Buffer */
struct ap_buffer_s
{
+ struct dq_entry_s dq_entry; /* Double linked queue entry */
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 */
+#ifdef CONFIG_AUDIO_MULTI_SESSION
+ FAR void *session; /* Associated session */
+#endif
+ apb_samp_t nmaxbytes; /* The maximum number of bytes */
+ apb_samp_t nbytes; /* The number of bytes used */
+ apb_samp_t curbyte; /* Next byte to be processed */
+ sem_t sem; /* Reference locking semaphore */
uint16_t flags; /* Buffer flags */
+ uint16_t crefs; /* Number of reference counts */
uint8_t samp[0]; /* Offset of the first sample */
} packed_struct;
+/* Structure defining the messages passed to a listening audio thread
+ * for dequeuing buffers and other operations. Also used to allocate
+ * and enqueue buffers via the AUDIOIOC_ALLOCBUFFER, AUDIOIOC_FREEBUFFER,
+ * and AUDIOIOC_ENQUEUEBUFFER ioctls.
+ */
+
+struct audio_msg_s
+{
+#ifdef CONFIG_AUDIO_MULTI_SESSION
+ FAR void *session; /* Associated channel */
+#endif
+ uint16_t msgId; /* Message ID */
+ union
+ {
+ FAR void * pPtr; /* Buffer being dequeued */
+ uint32_t data; /* Message data */
+ } u;
+};
+
+
+/* Strucure defining the built-in sounds */
+
+#ifdef CONFIG_AUDIO_BUILTIN_SOUNDS
+struct audio_sound_s
+{
+ const char *name; /* Name of the sound */
+ uint32_t id; /* ID of the sound */
+ uint32_t type; /* Type of sound */
+ uint32_t size; /* Number of bytes in the sound */
+ const uint8_t *data; /* Pointer to the data */
+};
+
+#endif
+
+/* Structure for allocating, freeing and enqueuing audio pipeline
+ * buffers via the AUDIOIOC_ALLOCBUFFER, AUDIOIOC_FREEBUFFER,
+ * and AUDIOIOC_ENQUEUEBUFFER ioctls.
+ */
+
+struct audio_buf_desc_s
+{
+#ifdef CONFIG_AUDIO_MULTI_SESSION
+ FAR void *session; /* Associated channel */
+#endif
+ uint16_t numbytes; /* Number of bytes to allocate */
+ union
+ {
+ FAR struct ap_buffer_s *pBuffer; /* Buffer to free / enqueue */
+ FAR struct ap_buffer_s **ppBuffer; /* Pointer to receive alloced buffer */
+ } u;
+};
+
/* Typedef for lower-level to upper-level callback for buffer dequeuing */
+#ifdef CONFIG_AUDIO_MULTI_SESSION
+typedef CODE void (*audio_callback_t)(FAR void *priv, uint16_t reason,
+ FAR struct ap_buffer_s *apb, uint16_t status, FAR void *session);
+#else
typedef CODE void (*audio_callback_t)(FAR void *priv, uint16_t reason,
FAR struct ap_buffer_s *apb, uint16_t status);
+#endif
/* 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
@@ -249,25 +419,29 @@ 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
+ * 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,
+ CODE int (*getcaps)(FAR struct audio_lowerhalf_s *dev, int type,
FAR struct audio_caps_s *pCaps);
/* This method is called to bind the lower-level driver to the upper-level
* driver and to configure the driver for a specific mode of
* operation defined by the parameters selected in supplied device caps
- * structure. The lower-level device should perform any initialization
- * needed to prepare for operations in the specified mode. It should not,
+ * structure. 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,
- audio_callback_t upper, FAR void *priv);
+#ifdef CONFIG_AUDIO_MULTI_SESSION
+ CODE int (*configure)(FAR struct audio_lowerhalf_s *dev,
+ FAR void *session, FAR const struct audio_caps_s *pCaps);
+#else
+ CODE int (*configure)(FAR struct audio_lowerhalf_s *dev,
+ FAR const struct audio_caps_s *pCaps);
+#endif
/* This method is called when the driver is closed. The lower half driver
* should stop processing audio data, including terminating any active
@@ -280,26 +454,75 @@ struct audio_ops_s
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
+ /* 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.
*/
+#ifdef CONFIG_AUDIO_MULTI_SESSION
+ CODE int (*start)(FAR struct audio_lowerhalf_s *dev, FAR void *session);
+#else
CODE int (*start)(FAR struct audio_lowerhalf_s *dev);
+#endif
/* Stop audio streaming and/or processing of enqueued Audio Pipeline Buffers */
+#ifndef CONFIG_AUDIO_EXCLUDE_STOP
+#ifdef CONFIG_AUDIO_MULTI_SESSION
+ CODE int (*stop)(FAR struct audio_lowerhalf_s *dev, FAR void *session);
+#else
CODE int (*stop)(FAR struct audio_lowerhalf_s *dev);
+#endif
+#endif
+
+ /* Pause the audio stream. Should keep current playback context active
+ * in case a resume is issued. Could be called and then followed by a stop.
+ */
+
+#ifndef CONFIG_AUDIO_EXCLUDE_PAUSE_RESUME
+#ifdef CONFIG_AUDIO_MULTI_SESSION
+ CODE int (*pause)(FAR struct audio_lowerhalf_s *dev, FAR void *session);
+#else
+ CODE int (*pause)(FAR struct audio_lowerhalf_s *dev);
+#endif
+
+ /* Resumes audio streaming after a pause */
+
+#ifdef CONFIG_AUDIO_MULTI_SESSION
+ CODE int (*resume)(FAR struct audio_lowerhalf_s *dev, FAR void *session);
+#else
+ CODE int (*resume)(FAR struct audio_lowerhalf_s *dev);
+#endif
+#endif /* CONFIG_AUDIO_EXCLUDE_PAUSE_RESUME */
+
+ /* Allocate an audio pipeline buffer. This routine provides the
+ * lower-half driver with the opportunity to perform special buffer
+ * allocation if needed, such as allocating from a specific memory
+ * region (DMA-able, etc.). If not supplied, then the top-half
+ * driver will perform a standard kumalloc using normal user-space
+ * memory region.
+ */
+
+ CODE int (*allocbuffer)(FAR struct audio_lowerhalf_s *dev,
+ FAR struct audio_buf_desc_s *apb);
- /* 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
- j* 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
+ /* Free an audio pipeline buffer. If the lower-level driver
+ * provides an allocbuffer routine, it should also provide the
+ * freebuffer routine to perform the free operation.
+ */
+
+ CODE int (*freebuffer)(FAR struct audio_lowerhalf_s *dev,
+ FAR struct audio_buf_desc_s *apb);
+
+ /* 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.
*/
@@ -316,6 +539,37 @@ struct audio_ops_s
CODE int (*ioctl)(FAR struct audio_lowerhalf_s *dev,
int cmd, unsigned long arg);
+
+ /* Lower-half logic may support platform-specific read commands */
+
+ CODE int (*read)(FAR struct audio_lowerhalf_s *dev,
+ FAR char *buffer, size_t buflen);
+
+ /* Lower-half logic may support platform-specific write commands */
+
+ CODE int (*write)(FAR struct audio_lowerhalf_s *dev,
+ FAR const char *buffer, size_t buflen);
+
+ /* Reserve a session (may only be one per device or may be multiple) for
+ * use by a client. Client software can open audio devices and issue
+ * AUDIOIOC_GETCAPS calls freely, but other operations require a
+ * reservation. A session reservation will assign a context that must
+ * be passed with
+ */
+
+#ifdef CONFIG_AUDIO_MULTI_SESSION
+ CODE int (*reserve)(FAR struct audio_lowerhalf_s *dev, FAR void **psession );
+#else
+ CODE int (*reserve)(FAR struct audio_lowerhalf_s *dev);
+#endif
+
+ /* Release a session. */
+
+#ifdef CONFIG_AUDIO_MULTI_SESSION
+ CODE int (*release)(FAR struct audio_lowerhalf_s *dev, FAR void *session );
+#else
+ CODE int (*release)(FAR struct audio_lowerhalf_s *dev);
+#endif
};
/* This structure is the generic form of state structure used by lower half
@@ -325,8 +579,8 @@ struct audio_ops_s
* 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
+ * 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.
*/
@@ -348,7 +602,7 @@ struct audio_lowerhalf_s
FAR void *priv;
- /* The custom Audio device state structure may include additional fields
+ /* The custom Audio device state structure may include additional fields
* after the pointer to the Audio callback structure.
*/
};
@@ -363,7 +617,8 @@ struct audio_lowerhalf_s
#ifdef __cplusplus
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
@@ -387,7 +642,7 @@ extern "C" {
* 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",
+ * 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
@@ -398,7 +653,7 @@ extern "C" {
*
****************************************************************************/
-EXTERN int audio_register(FAR const char *name, FAR struct audio_lowerhalf_s *dev);
+int audio_register(FAR const char *name, FAR struct audio_lowerhalf_s *dev);
/****************************************************************************
* Name: abp_alloc
@@ -410,13 +665,14 @@ EXTERN int audio_register(FAR const char *name, FAR struct audio_lowerhalf_s *de
* and then call apb_prepare, passing it the allocated memory.
*
* Input parameters:
+ * bufdesc: Pointer to a buffer descriptor
*
* Returned Value:
* Pointer to the allocated buffer or NULL if no memory.
*
****************************************************************************/
-FAR struct ap_buffer_s *apb_alloc(int type, int sampleCount);
+int apb_alloc(FAR struct audio_buf_desc_s *bufdesc);
/****************************************************************************
* Name: abp_prepare
@@ -437,8 +693,8 @@ FAR struct ap_buffer_s *apb_alloc(int type, int sampleCount);
*
****************************************************************************/
-EXTERN void apb_prepare(struct ap_buffer_s *apb, int8_t allocmode, uint8_t format,
- uint8_t subformat, apb_samp_t maxsamples);
+void apb_prepare(struct ap_buffer_s *apb, int8_t allocmode, uint8_t format,
+ uint8_t subformat, apb_samp_t maxsamples);
/****************************************************************************
* Name: apb_free
@@ -447,7 +703,7 @@ EXTERN void apb_prepare(struct ap_buffer_s *apb, int8_t allocmode, uint8_t forma
*
****************************************************************************/
-EXTERN void apb_free(FAR struct ap_buffer_s *apb);
+void apb_free(FAR struct ap_buffer_s *apb);
/****************************************************************************
* Name: apb_reference
@@ -458,7 +714,7 @@ EXTERN void apb_free(FAR struct ap_buffer_s *apb);
*
****************************************************************************/
-EXTERN void apb_reference(FAR struct ap_buffer_s *apb);
+void apb_reference(FAR struct ap_buffer_s *apb);
/****************************************************************************
* Platform-Dependent "Lower-Half" Audio Driver Interfaces