audio/alc5658char: add reference alc5658 character device driver
authorIvan <ivan.galkin@samsung.com>
Thu, 27 Jul 2017 05:36:39 +0000 (14:36 +0900)
committerIvan Galkin <ivan.galkin@samsung.com>
Sun, 27 Aug 2017 06:23:43 +0000 (15:23 +0900)
This patch contains code for ALC5658 codec character device driver.
This code is for reference only.

Change-Id: I1a0bb368cede15130b5f6821f575884eba8427e6
Signed-off-by: Ivan <ivan.galkin@samsung.com>
Signed-off-by: Bongryul Lee <bongryul.lee@samsung.com>
Signed-off-by: Junhwan Park <junhwan.park@samsung.com>
build/configs/artik053/audio/defconfig
os/arch/arm/src/artik053/src/Makefile
os/arch/arm/src/artik053/src/artik053_alc5658char.c [new file with mode: 0644]
os/arch/arm/src/artik053/src/artik053_boot.c
os/drivers/audio/Kconfig
os/drivers/audio/Make.defs
os/drivers/audio/alc5658char.c [new file with mode: 0644]
os/drivers/audio/alc5658char.h [new file with mode: 0644]
os/include/tinyara/audio/audio.h

index 1687cd6..572dc60 100644 (file)
@@ -465,7 +465,6 @@ CONFIG_SPI=y
 CONFIG_GPIO=y
 CONFIG_I2S=y
 CONFIG_AUDIO_DEVICES=y
-# CONFIG_AUDIO_I2SCHAR is not set
 # CONFIG_AUDIO_NULL is not set
 CONFIG_AUDIO_ALC5658=y
 CONFIG_ALC5658_INITVOLUME=250
index 8cb3e19..637afbc 100644 (file)
@@ -61,6 +61,8 @@ CSRCS = artik053_boot.c \
 
 ifeq ($(CONFIG_AUDIO_ALC5658),y)
 CSRCS += artik053_alc5658.c
+else ifeq ($(CONFIG_AUDIO_ALC5658CHAR),y)
+CSRCS += artik053_alc5658char.c
 endif
 
 ifeq ($(CONFIG_MTD_PROGMEM),y)
diff --git a/os/arch/arm/src/artik053/src/artik053_alc5658char.c b/os/arch/arm/src/artik053/src/artik053_alc5658char.c
new file mode 100644 (file)
index 0000000..5076d47
--- /dev/null
@@ -0,0 +1,153 @@
+/****************************************************************************
+ *
+ * Copyright 2017 Samsung Electronics All Rights Reserved.
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ * http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing,
+ * software distributed under the License is distributed on an
+ * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND,
+ * either express or implied. See the License for the specific
+ * language governing permissions and limitations under the License.
+ *
+ ****************************************************************************/
+/************************************************************************************
+ * arch/arm/src/artik053/src/artik053_alc5658char.c
+ *
+ *   Copyright (C) 2014 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 <tinyara/config.h>
+
+#include <sys/types.h>
+#include <errno.h>
+#include <debug.h>
+#include <tinyara/clock.h>
+
+#if defined(CONFIG_AUDIO_ALC5658CHAR) && defined(CONFIG_S5J_I2S) && defined(CONFIG_S5J_I2C)
+
+#include <tinyara/i2c.h>
+
+#include "s5j_i2s.h"
+#include "s5j_i2c.h"
+#include <tinyara/audio/i2s.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+#ifndef CONFIG_ALC5658_I2C_PORT
+#define CONFIG_ALC5658_I2C_PORT 1
+#endif
+
+#define ALC5658_I2C_ADDR 0x1A
+#define ALC5658_I2C_FREQ 100000
+#define ALC5658_I2C_ADDRLEN 7
+
+int alc5658char_register(FAR struct i2s_dev_s *i2s, FAR struct i2c_dev_s *i2c, FAR struct i2c_config_s *i2c_config, int minor);
+
+/************************************************************************************
+ * Private Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+static struct i2c_config_s g_i2c_config = {
+       .frequency = ALC5658_I2C_FREQ,
+       .address = ALC5658_I2C_ADDR,
+       .addrlen = ALC5658_I2C_ADDRLEN,
+};
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: s5j_alc5658char_initialize
+ *
+ * Description:
+ *   All architectures must provide the following interface in order to work with
+ *   apps/examples/alc5658char_test
+ *
+ ************************************************************************************/
+int s5j_alc5658char_initialize(int minor)
+{
+       static bool initialized;
+       struct i2c_dev_s *i2c;
+       struct i2s_dev_s *i2s;
+       int ret;
+
+       /* Have we already initialized? */
+
+       if (!initialized) {
+
+               i2c = up_i2cinitialize(CONFIG_ALC5658_I2C_PORT);
+               if (!i2c) {
+                       auddbg("ERROR: Failed to initialize CODEC I2C%d\n");
+                       return -ENODEV;
+               }
+
+               /* Call s5j_i2s_initialize() to get an instance of the I2S interface */
+               i2s = s5j_i2s_initialize();
+               if (!i2s) {
+                       auddbg("ERROR: Failed to get the S5J I2S driver\n");
+                       return -ENODEV;
+               }
+
+               /* Register the ALC5658 character driver at "/dev/alc5658charN" */
+
+               ret = alc5658char_register(i2s, i2c, &g_i2c_config, minor);
+               if (ret < 0) {
+                       auddbg("ERROR: i2schar_register failed: %d\n", ret);
+                       return ret;
+               }
+
+               /* Now we are initialized */
+
+               initialized = true;
+       }
+
+       return OK;
+}
+#endif
index d1b5bec..2a6b2db 100644 (file)
@@ -214,8 +214,10 @@ void board_initialize(void)
        board_gpio_initialize();
        board_i2c_initialize();
 
-#ifdef CONFIG_AUDIO_ALC5658
+#if defined(CONFIG_AUDIO_ALC5658)
        s5j_alc5658_initialize(0);
+#elif defined(CONFIG_AUDIO_ALC5658CHAR)
+       s5j_alc5658char_initialize(0);
 #endif
 }
 #endif /* CONFIG_BOARD_INITIALIZE */
index 214d8a8..6865b26 100755 (executable)
@@ -3,39 +3,6 @@
 # see kconfig-language at https://www.kernel.org/doc/Documentation/kbuild/kconfig-language.txt
 #
 
-config AUDIO_I2SCHAR
-       bool "I2S character driver (for testing only)"
-       default n
-       depends on I2S && AUDIO
-       ---help---
-               This selection enables a simple character driver that supports I2S
-               transfers via a read() and write().  The intent of this driver is to
-               support I2S testing.  It is not an audio driver but does conform to
-               some of the buffer management heuristics of an audio driver.  It is
-               not suitable for use in any real driver application in its current
-               form.
-
-if AUDIO_I2SCHAR
-
-config AUDIO_I2SCHAR_RXTIMEOUT
-       int "RX timeout"
-       default 0
-       ---help---
-               This is a fixed timeout value that will be used for all receiver
-               transfers.  This is in units of system clock ticks (configurable).
-               The special value of zero disables RX timeouts.  Default: 0
-
-config AUDIO_I2SCHAR_TXTIMEOUT
-       int "TX timeout"
-       default 0
-       ---help---
-               This is a fixed timeout value that will be used for all transmitter
-               transfers.  This is in units of system clock ticks (configurable).
-               The special value of zero disables RX timeouts.  Default: 0
-
-endif #AUDIO_I2SCHAR
-
-
 config AUDIO_NULL
        bool "NULL audio device"
        default n
@@ -64,64 +31,86 @@ config AUDIO_NULL_WORKER_STACKSIZE
 
 endif # AUDIO_NULL
 
+choice
+       prompt "Select how to use the alc5658"
+
 config AUDIO_ALC5658
-        bool "ALC5658 audio chip"
-        default n
-        depends on AUDIO
-        ---help---
-                Select to enable support for the ALC5658 Audio codec by Wolfson
-                Microelectonics.  This chip is a lower level audio chip.. basically
-                an exotic D-to-A.  It includes no built-in support for audio CODECS
-                The ALC5658 provides:
-
-                        - Low power consumption
-                        - High SNR
-                        - Stereo digital microphone input
-                        - Digital Dynamic Range Controller (compressor / limiter)
-                        - Digital sidetone mixing
-                        - Ground-referenced headphone driver
-                        - Ground-referenced line outputs
-
-                NOTE: This driver also depends on both I2C and I2S support although
-                that dependency is not explicit here.
+       bool "ALC5658 audio chip"
+       depends on AUDIO
+       ---help---
+               Select to enable support for the ALC5658 Audio codec by Realtek
+               NOTE: This driver also depends on both I2C and I2S support although
+               that dependency is not explicit here.
 
 if AUDIO_ALC5658
 
 config ALC5658_INITVOLUME
-        int "ALC5658 initial volume setting"
-        default 250
+       int "ALC5658 initial volume setting"
+       default 250
 
 config ALC5658_INFLIGHT
-        int "ALC5658 maximum in-flight audio buffers"
-        default 2
+       int "ALC5658 maximum in-flight audio buffers"
+       default 2
 
 config ALC5658_MSG_PRIO
-        int "ALC5658 message priority"
-        default 1
+       int "ALC5658 message priority"
+       default 1
 
 config ALC5658_BUFFER_SIZE
-        int "ALC5658 preferred buffer size"
-        default 8192
+       int "ALC5658 preferred buffer size"
+       default 8192
 
 config ALC5658_NUM_BUFFERS
-        int "ALC5658 preferred number of buffers"
-        default 4
+       int "ALC5658 preferred number of buffers"
+       default 4
 
 config ALC5658_WORKER_STACKSIZE
-        int "ALC5658 worker thread stack size"
-        default 768
+       int "ALC5658 worker thread stack size"
+       default 768
 
 config ALC5658_REGDUMP
-        bool "ALC5658 register dump"
-        default n
-        ---help---
-                Enable logic to dump the contents of all ALC5658 registers.
+       bool "ALC5658 register dump"
+       default n
+       ---help---
+               Enable logic to dump the contents of all ALC5658 registers.
 
 config ALC5658_CLKDEBUG
-        bool "ALC5658 clock analysis"
-        default n
-        ---help---
-                Enable logic to analyze ALC5658 clock configuation.
+       bool "ALC5658 clock analysis"
+       default n
+       ---help---
+               Enable logic to analyze ALC5658 clock configuation.
 
 endif # AUDIO_ALC5658
 
+config AUDIO_ALC5658CHAR
+       bool "ALC5658 Character Driver (for testing and demo only)"
+       depends on I2S && AUDIO && I2C
+       ---help---
+               This selection enables a simple character driver that supports ALC codec
+               transfers via a read() and write() ioctl.  The intent of this driver is to
+               support ALC codec operation.  It is not an audio driver but does conform to
+               some of the buffer management heuristics of an audio driver.  It can be used
+               as real driver application with come restrictions.
+               form.
+
+if AUDIO_ALC5658CHAR
+
+config AUDIO_ALC5658CHAR_RXTIMEOUT
+       int "RX timeout"
+       default 0
+       ---help---
+               This is a fixed timeout value that will be used for all receiver
+               transfers.  This is in units of system clock ticks (configurable).
+               The special value of zero disables RX timeouts.  Default: 0
+
+config AUDIO_ALC5658CHAR_TXTIMEOUT
+       int "TX timeout"
+       default 0
+       ---help---
+               This is a fixed timeout value that will be used for all transmitter
+               transfers.  This is in units of system clock ticks (configurable).
+               The special value of zero disables RX timeouts.  Default: 0
+
+endif # AUDIO_ALC5658CHAR
+
+endchoice
index 81cbc5a..b4cd170 100644 (file)
@@ -60,8 +60,8 @@ ifeq ($(CONFIG_AUDIO_NULL),y)
 CSRCS += audio_null.c
 endif
 
-ifeq ($(CONFIG_AUDIO_I2SCHAR),y)
-CSRCS += i2schar.c
+ifeq ($(CONFIG_AUDIO_ALC5658CHAR),y)
+CSRCS += alc5658char.c
 endif
 
 ifeq ($(CONFIG_AUDIO_ALC5658),y)
diff --git a/os/drivers/audio/alc5658char.c b/os/drivers/audio/alc5658char.c
new file mode 100644 (file)
index 0000000..b10001a
--- /dev/null
@@ -0,0 +1,834 @@
+/****************************************************************************
+ *
+ * Copyright 2016 Samsung Electronics All Rights Reserved.
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ * http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing,
+ * software distributed under the License is distributed on an
+ * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND,
+ * either express or implied. See the License for the specific
+ * language governing permissions and limitations under the License.
+ *
+ ****************************************************************************/
+/****************************************************************************
+ * drivers/audio/alc5658char.c
+ *
+ * This is a simple character driver for testing I2C.  It is not an audio
+ * driver but does conform to some of the buffer management heuristics of an
+ * audio driver.  It is not suitable for use in any real driver application
+ * in its current form.
+ *
+ *   Copyright (C) 2013 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 <tinyara/config.h>
+
+#include <sys/types.h>
+
+#include <stdint.h>
+#include <stdio.h>
+#include <fcntl.h>
+#include <string.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <tinyara/kmalloc.h>
+#include <tinyara/fs/fs.h>
+#include <tinyara/audio/audio.h>
+#include <tinyara/audio/i2s.h>
+#include <tinyara/i2c.h>
+
+#include <tinyara/clock.h>
+
+#include "alc5658char.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+
+#ifndef CONFIG_AUDIO_I2SCHAR_RXTIMEOUT
+#define CONFIG_AUDIO_I2SCHAR_RXTIMEOUT 0
+#endif
+
+#ifndef CONFIG_AUDIO_I2SCHAR_TXTIMEOUT
+#define CONFIG_AUDIO_I2SCHAR_TXTIMEOUT 0
+#endif
+
+#ifndef CONFIG_AUDIO_I2SCHAR_NRXBUF
+#define CONFIG_AUDIO_I2SCHAR_NRXBUF  8
+#endif
+
+#ifndef CONFIG_AUDIO_I2SCHAR_NTXBUF
+#define CONFIG_AUDIO_I2SCHAR_NTXBUF  8
+#endif
+
+/* Device naming ************************************************************/
+#define DEVNAME_FMT    "/dev/alc5658char%d"
+#define DEVNAME_FMTLEN (16 + 3 + 1)
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct alc5658char_dev_s {
+       FAR struct i2s_dev_s *i2s;      /* The lower half i2s driver */
+       FAR struct i2c_dev_s *i2c;      /* i2c bus access ops */
+       FAR struct i2c_config_s *i2c_config;
+
+#ifdef AUDIO_BUFFERS_REUSE
+       /*If we decide to reuse bufferes use next queues*/
+       struct dq_queue_s doneq;        /* Queue of sent buffers to be reused */
+       sem_t donesem;                          /* Protect dq */
+#endif
+
+       struct dq_queue_s rxedq;        /* Queue of received audio IN buffers */
+       sem_t rxsem;                            /* Protect RX Q and rx_cnt */
+       sem_t cnt_rxsem;                        /* Counting semaphore to block receiving thread if no data is received yet */
+       int rx_cnt;                                     /* Count allocated RX buffers */
+
+       sem_t alloc;                            /* Counting semaphore for Alloc TX buffers, and block allocator if needed */
+
+       sem_t exclsem;                          /* Assures mutually exclusive access */
+
+       uint32_t samprate;                      /* 8000, 44100, ... */
+       uint8_t bpsamp;                         /* Bits per sample: 8 bits = 8, 16 bits = 16 */
+       uint8_t nchannels;                      /* Mono=1, Stereo=2 */
+
+       uint8_t volume;
+       int16_t balance;                        /* Current balance level */
+       int16_t micgain;                        /* Current mic gain level */
+
+       bool running;                           /* True: Worker thread is running */
+       bool paused;                            /* True: Playing is paused */
+       bool mute;                                      /* True: Output is muted */
+       bool terminating;                       /* True: Stop requested */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+/* I2S callback function */
+
+static void alc5658char_rxcallback(FAR struct i2s_dev_s *dev, FAR struct ap_buffer_s *apb, FAR void *arg, int result);
+static void alc5658char_txcallback(FAR struct i2s_dev_s *dev, FAR struct ap_buffer_s *apb, FAR void *arg, int result);
+
+/* Character driver methods */
+
+static ssize_t alc5658char_read(FAR struct file *filep, FAR char *buffer, size_t buflen);
+static ssize_t alc5658char_write(FAR struct file *filep, FAR const char *buffer, size_t buflen);
+
+static ssize_t alc5658char_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static const struct file_operations alc5658char_fops = {
+       NULL,                                           /* open  */
+       NULL,                                           /* close */
+       alc5658char_read,                       /* read  */
+       alc5658char_write,                      /* write */
+       NULL,                                           /* seek  */
+       alc5658char_ioctl,                      /* ioctl */
+#ifndef CONFIG_DISABLE_POLL
+       NULL,                                           /* poll  */
+#endif
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+static void delay(unsigned int mS)
+{
+       systime_t start = clock_systimer();
+
+       mS = mS / MSEC_PER_TICK + 1;
+
+       while (1) {
+               if ((start + mS) < clock_systimer()) {
+                       return;
+               }
+       }
+}
+
+/****************************************************************************
+ * Name: alc5658char_readreg
+ *
+ * Description
+ *    Read the specified 16-bit register from the ALC5658 device.
+ *
+ ****************************************************************************/
+static uint16_t alc5658char_readreg(FAR struct alc5658char_dev_s *priv, uint16_t regaddr)
+{
+
+       int32_t ret;
+       uint8_t reg[2];
+       uint16_t regval;
+       FAR struct i2c_dev_s *dev = priv->i2c;
+       FAR struct i2c_config_s *alc5658char_i2c_config = priv->i2c_config;
+
+       reg[0] = ((char *)&regaddr)[1];
+       reg[1] = ((char *)&regaddr)[0];
+
+       ret = i2c_write(dev, alc5658char_i2c_config, reg, 2);
+       if (ret < 0) {
+               auddbg("Error, cannot read reg %x\n", regaddr);
+               return 0;
+       }
+
+       ret = i2c_read(dev, alc5658char_i2c_config, reg, 2);
+       if (ret < 0) {
+               auddbg("Error, cannot read reg %x\n", regaddr);
+               return 0;
+       }
+
+       regval = ((uint16_t) reg[0] << 8) | (uint16_t) reg[1];
+
+       return regval;
+}
+
+/************************************************************************************
+ * Name: alc5658char_writereg
+ *
+ * Description:
+ *   Write the specified 16-bit register to the ALC5658 device.
+ *
+ ************************************************************************************/
+
+static void alc5658char_writereg(FAR struct alc5658char_dev_s *priv, uint16_t regaddr, uint16_t regval)
+{
+       int32_t ret;
+       uint8_t reg[4];
+       FAR struct i2c_dev_s *dev = priv->i2c;
+       FAR struct i2c_config_s *alc5658char_i2c_config = priv->i2c_config;
+
+       reg[0] = ((char *)&regaddr)[1];
+       reg[1] = ((char *)&regaddr)[0];
+
+       reg[2] = ((char *)&regval)[1];
+       reg[3] = ((char *)&regval)[0];
+
+       ret = i2c_write(dev, alc5658char_i2c_config, (uint8_t *) reg, 4);
+       if (ret < 0) {
+               auddbg("Error, cannot write reg %x\n", regaddr);
+       }
+}
+
+static uint16_t alc5658char_modifyreg(FAR struct alc5658char_dev_s *priv, uint16_t regaddr, uint16_t set, uint16_t clear)
+{
+       uint16_t data;
+
+       data = alc5658char_readreg(priv, regaddr);
+       data &= ~clear;
+       data |= set;
+
+       alc5658char_writereg(priv, regaddr, data);
+       return alc5658char_readreg(priv, regaddr);
+}
+
+static void alc5658char_i2c_script(FAR struct alc5658char_dev_s *priv, t_codec_init_script_entry *script, uint32_t size)
+{
+       uint32_t i;
+       uint16_t ret;
+
+       for (i = 0; i < size; i++) {
+               ret = alc5658char_modifyreg(priv, script[i].addr, script[i].val, 0xFFFF);
+
+               delay(script[i].delay);
+       }
+}
+
+/****************************************************************************
+ * Name: alc5658char_setdatawidth
+ *
+ * Description:
+ *   Set the 8- 16- 24- bit data modes
+ *
+ ****************************************************************************/
+
+static void alc5658char_setdatawidth(FAR struct alc5658char_dev_s *priv)
+{
+       I2S_TXDATAWIDTH(priv->i2s, priv->bpsamp);
+}
+
+/****************************************************************************
+ * Name: alc5658char_setbitrate
+ *
+ * Description:
+ *
+ ****************************************************************************/
+
+static void alc5658char_setbitrate(FAR struct alc5658char_dev_s *priv)
+{
+}
+
+/************************************************************************************
+ * Name: alc5658char_setvolume
+ *
+ * Description:
+ *   Set the right and left volume values in the ALC5658 device based on the current
+ *   volume and balance settings.
+ *
+ ************************************************************************************/
+
+static void alc5658char_setvolume(FAR struct alc5658char_dev_s *priv)
+{
+       uint16_t vol_l, vol_r;
+       int16_t bal = priv->balance;
+
+       /* ADD VOLUME CODE HERE */
+       vol_l = priv->volume;
+       vol_r = priv->volume;
+
+       if (bal > 0) {
+               vol_l = vol_l - vol_l * abs(bal) / 1000;
+       }
+
+       if (bal < 0) {
+               vol_r = vol_r - vol_l * abs(bal) / 1000;
+       }
+
+       if (priv->mute) {
+               alc5658char_writereg(priv, ACL5658_HPOUT_MUTE, 0x8080);
+       } else {
+               alc5658char_writereg(priv, ACL5658_HPOUT_MUTE, 0x0000);
+       }
+
+       alc5658char_writereg(priv, ACL5658_HPOUT_VLML, vol_l << 8);
+       alc5658char_writereg(priv, ACL5658_HPOUT_VLMR, vol_r << 8);
+       audvdbg("MUTE %x, VOLL %x VOLR %x\n", (uint32_t) alc5658char_readreg(priv, ACL5658_HPOUT_MUTE), (uint32_t) alc5658char_readreg(priv, ACL5658_HPOUT_VLML), (uint32_t) alc5658char_readreg(priv, ACL5658_HPOUT_VLMR));
+
+}
+
+/************************************************************************************
+ * Name: alc5658char_setmic
+ *
+ * Description:
+ *   Set Mic gain and some other related options if needed
+ *
+ ************************************************************************************/
+
+static void alc5658char_setmic(FAR struct alc5658char_dev_s *priv)
+{
+       alc5658char_writereg(priv, ACL5658_IN1_CTRL, (priv->micgain + 16) << 8);
+       audvdbg("MIC GAIN 0x%x\n", (uint32_t) alc5658char_readreg(priv, ACL5658_IN1_CTRL));
+}
+
+/****************************************************************************
+ * Name: alc5658char_configure
+ *
+ * Description:
+ *   Configure the audio device for the specified  mode of operation.
+ *
+ ****************************************************************************/
+
+static int alc5658char_configure(FAR struct alc5658char_dev_s *priv, FAR const struct audio_caps_s *caps)
+{
+       int ret = OK;
+
+       DEBUGASSERT(priv && caps);
+       audvdbg("ac_type: %d\n", caps->ac_type);
+
+       /* Process the configure operation */
+
+       switch (caps->ac_type) {
+       case AUDIO_TYPE_FEATURE:
+               audvdbg("  AUDIO_TYPE_FEATURE\n");
+
+               /* Process based on Feature Unit */
+
+               switch (caps->ac_format.hw) {
+               case AUDIO_FU_VOLUME: {
+                       /* Set the volume 0 ~ 1000 */
+                       if (caps->ac_controls.hw[0] <= 1000) {
+                               priv->volume = 63 - 63 * caps->ac_controls.hw[0] / 1000;
+                       }
+                       alc5658char_setvolume(priv);
+                       audvdbg("    Volume: %d\n", priv->volume);
+               }
+               break;
+               case AUDIO_FU_MUTE: {
+                       /* Set the mute true/false */
+                       priv->mute = !!(caps->ac_controls.b[0]);
+                       audvdbg("    Mute: %d\n", priv->mute);
+                       alc5658char_setvolume(priv);
+               }
+               break;
+               case AUDIO_FU_BALANCE: {
+                       /* Set the balamce -1000 ~ 0 ~ 1000 */
+                       int16_t bal = caps->ac_controls.hw[0];
+
+                       if (abs(bal) <= 1000) {
+                               priv->balance = bal;
+                       }
+                       audvdbg("    Balance: %d\n", priv->balance);
+                       alc5658char_setvolume(priv);
+               }
+               break;
+               case AUDIO_FU_MICGAIN: {
+                       /* Set MIC gain */
+                       /* Values -16 ~ 0 ~ 53 equal to -12dB ~ 0dB ~ 39.75 */
+                       int16_t gain = caps->ac_controls.hw[0];
+
+                       if ((gain >= -16) && (gain <= 53)) {
+                               priv->micgain = gain;
+                               audvdbg("    Mic Gain: %d\n", priv->micgain);
+                               alc5658char_setmic(priv);
+                       } else {
+                               audvdbg("    Mic Gain request is out of range, unchanged: %d\n", priv->micgain);
+                       }
+               }
+               break;
+
+               default:
+                       auddbg("    ERROR: Unrecognized feature unit\n");
+                       ret = -ENOTTY;
+                       break;
+               }
+               break;
+
+       case AUDIO_TYPE_OUTPUT: {
+               audvdbg("  AUDIO_TYPE_OUTPUT:\n");
+               audvdbg("    Number of channels: %u\n", caps->ac_channels);
+               audvdbg("    Sample rate:        %u\n", caps->ac_controls.hw[0]);
+               audvdbg("    Sample width:       %u\n", caps->ac_controls.b[2]);
+
+               /* Verify that all of the requested values are supported */
+
+               ret = -ERANGE;
+               if (caps->ac_channels != 1 && caps->ac_channels != 2) {
+                       auddbg("ERROR: Unsupported number of channels: %d\n", caps->ac_channels);
+                       break;
+               }
+
+               if (caps->ac_controls.b[2] != 8 && caps->ac_controls.b[2] != 16) {
+                       auddbg("ERROR: Unsupported bits per sample: %d\n", caps->ac_controls.b[2]);
+                       break;
+               }
+
+               /* Save the current stream configuration */
+
+               priv->samprate = caps->ac_controls.hw[0];
+               priv->nchannels = caps->ac_channels;
+               priv->bpsamp = caps->ac_controls.b[2];
+
+               /* alc5658char_setdatawidth(priv); */
+               /* alc5658char_setbitrate(priv); */
+
+               ret = OK;
+       }
+       break;
+
+       case AUDIO_TYPE_PROCESSING:
+               break;
+       }
+
+       return ret;
+}
+
+/****************************************************************************
+ * Name: alc5658char_start
+ *
+ * Description:
+ *   Configure the audio device for the specified  mode of operation.
+ *
+ ****************************************************************************/
+
+static int alc5658char_start(FAR struct alc5658char_dev_s *priv, FAR const struct audio_caps_s *caps)
+{
+       int ret = OK;
+
+       alc5658char_setdatawidth(priv);
+
+       /* Init codec here only for debugging purposes. Remove later. */
+       alc5658char_i2c_script(priv, codec_init_inout_script1, sizeof(codec_init_inout_script1) / sizeof(t_codec_init_script_entry));
+
+       switch (priv->samprate) {
+       case AUDIO_SAMP_RATE_8K:
+               alc5658char_i2c_script(priv, codec_init_pll_8K, sizeof(codec_init_pll_8K) / sizeof(t_codec_init_script_entry));
+               break;
+       case AUDIO_SAMP_RATE_11K:
+               alc5658char_i2c_script(priv, codec_init_pll_11K, sizeof(codec_init_pll_11K) / sizeof(t_codec_init_script_entry));
+               break;
+       case AUDIO_SAMP_RATE_16K:
+               alc5658char_i2c_script(priv, codec_init_pll_16K, sizeof(codec_init_pll_16K) / sizeof(t_codec_init_script_entry));
+               break;
+       case AUDIO_SAMP_RATE_22K:
+               alc5658char_i2c_script(priv, codec_init_pll_22K, sizeof(codec_init_pll_22K) / sizeof(t_codec_init_script_entry));
+               break;
+       case AUDIO_SAMP_RATE_32K:
+               alc5658char_i2c_script(priv, codec_init_pll_32K, sizeof(codec_init_pll_32K) / sizeof(t_codec_init_script_entry));
+               break;
+       case AUDIO_SAMP_RATE_44K:
+               alc5658char_i2c_script(priv, codec_init_pll_44K, sizeof(codec_init_pll_44K) / sizeof(t_codec_init_script_entry));
+               break;
+       case AUDIO_SAMP_RATE_48K:
+       default:
+               alc5658char_i2c_script(priv, codec_init_pll_48K, sizeof(codec_init_pll_48K) / sizeof(t_codec_init_script_entry));
+
+       };
+
+       alc5658char_i2c_script(priv, codec_init_inout_script2, sizeof(codec_init_inout_script2) / sizeof(t_codec_init_script_entry));
+
+       return ret;
+}
+
+static int alc5658char_stop(FAR struct alc5658char_dev_s *priv, FAR const struct audio_caps_s *caps)
+{
+       int ret = OK;
+       /* Init codec here only for debugging purposes. Remove later. */
+
+       alc5658char_i2c_script(priv, codec_stop_script, sizeof(codec_stop_script) / sizeof(t_codec_init_script_entry));
+       return ret;
+}
+
+/****************************************************************************
+ * Name: alc5658char_rxcallback
+ *
+ * Description:
+ *   I2S RX transfer complete callback.
+ *
+ *   NOTE: In this test driver, the RX is simply dumped in the bit bucket.
+ *   You would not do this in a real application. You would return the
+ *   received data to the caller via some IPC.
+ *
+ *   Also, the test buffer is simply freed.  This will work if this driver
+ *   has the sole reference to buffer; in that case the buffer will be freed.
+ *   Otherwise -- memory leak!  A more efficient design would recycle the
+ *   audio buffers.
+ *
+ ****************************************************************************/
+
+static void alc5658char_rxcallback(FAR struct i2s_dev_s *dev, FAR struct ap_buffer_s *apb, FAR void *arg, int result)
+{
+       FAR struct alc5658char_dev_s *priv = (FAR struct alc5658char_dev_s *)arg;
+
+       DEBUGASSERT(priv && apb);
+       audvdbg("apb=%p nbytes=%d result=%d crefs=%d\n", apb, apb->nbytes, result, apb->crefs);
+
+       sem_wait(&priv->rxsem);
+       /* we have some data, read ... */
+       dq_addlast((FAR dq_entry_t *) apb, &priv->rxedq);
+       sem_post(&priv->rxsem);
+
+       /* Let the waiting thread to capture received data */
+       sem_post(&priv->cnt_rxsem);
+}
+
+/****************************************************************************
+ * Name: alc5658char_txcallback
+ *
+ * Description:
+ *   I2S TX transfer complete callback
+ *
+ *   NOTE: The test buffer is simply freed.  This will work if this driver
+ *   has the sole reference to buffer; in that case the buffer will be freed.
+ *   Otherwise -- memory leak!  A more efficient design would recycle the
+ *   audio buffers.
+ *
+ ****************************************************************************/
+
+static void alc5658char_txcallback(FAR struct i2s_dev_s *dev, FAR struct ap_buffer_s *apb, FAR void *arg, int result)
+{
+       FAR struct alc5658char_dev_s *priv = (FAR struct alc5658char_dev_s *)arg;
+
+       DEBUGASSERT(priv && apb);
+       audvdbg("apb=%p nbytes=%d result=%d crefs=%d\n", apb, apb->nbytes, result, apb->crefs);
+
+       /* Free buffer here ... completety, if not reused */
+       apb_free(apb);
+
+       /* Let to alloc next buffer if pull was full */
+       sem_post(&priv->alloc);
+}
+
+/****************************************************************************
+ * Name: alc5658char_read
+ *
+ * Description:
+ *   Standard character driver read method
+ *
+ ****************************************************************************/
+
+static ssize_t alc5658char_read(FAR struct file *filep, FAR char *buffer, size_t buflen)
+{
+       return 0;
+}
+
+/****************************************************************************
+ * Name: alc5658char_write
+ *
+ * Description:
+ *   Standard character driver write method
+ *
+ ****************************************************************************/
+
+static ssize_t alc5658char_write(FAR struct file *filep, FAR const char *buffer, size_t buflen)
+{
+       return 0;
+}
+
+/************************************************************************************
+ * Name: alc5658char_ioctl
+ *
+ * Description:
+ *   The standard ioctl method.  This is where ALL of the Audio work is done.
+ *
+ ************************************************************************************/
+
+static ssize_t alc5658char_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
+{
+       FAR struct inode *inode = filep->f_inode;
+       FAR struct alc5658char_dev_s *priv;
+       FAR struct audio_buf_desc_s *bufdesc;
+       struct ap_buffer_s *apb;
+       int ret;
+
+       /* Get our private data structure */
+       DEBUGASSERT(filep);
+
+       inode = filep->f_inode;
+       DEBUGASSERT(inode);
+
+       priv = (FAR struct alc5658char_dev_s *)inode->i_private;
+       DEBUGASSERT(priv);
+
+       ret = 0;
+
+       switch (cmd) {
+
+       /* Alloc buffer for further TX operation. Will be filled by user APP. */
+       case AUDIOIOC_ALLOCBUFFER: {
+               audvdbg("AUDIOIOC_ALLOCBUFFER, arg - %ld\n", arg);
+
+               bufdesc = (FAR struct audio_buf_desc_s *)arg;
+               /* We will be waiting here is if we reached max number of allocated TX buffers */
+               sem_wait(&priv->alloc);
+               ret = apb_alloc(bufdesc);
+       }
+       break;
+
+       /* Free buffer we received at DEQUEUE with TXed data. */
+       case AUDIOIOC_FREEBUFFER: {
+               audvdbg("AUDIOIOC_FREEBUFFER, arg - %ld\n", arg);
+
+               bufdesc = (FAR struct audio_buf_desc_s *)arg;
+               DEBUGASSERT(bufdesc->u.pBuffer != NULL);
+
+               apb_free(bufdesc->u.pBuffer);
+
+               /* decrement number of allocated rx buffers */
+               DEBUGASSERT(priv->rx_cnt > 0);
+
+               sem_wait(&priv->rxsem);
+               priv->rx_cnt--;
+               sem_post(&priv->rxsem);
+
+               ret = sizeof(struct audio_buf_desc_s);
+       }
+       break;
+
+       /* Put buffer into TX queue. callback will be called after buffer is transferred */
+       case AUDIOIOC_ENQUEUEBUFFER: {
+               audvdbg("AUDIOIOC_ENQUEUEBUFFER, arg - %ld\n", arg);
+
+               bufdesc = (FAR struct audio_buf_desc_s *)arg;
+               ret = I2S_SEND(priv->i2s, bufdesc->u.pBuffer, alc5658char_txcallback, priv, CONFIG_AUDIO_I2SCHAR_TXTIMEOUT);
+
+       }
+       break;
+
+       /* Request RXed data. Before receive anything we allocate and enqueue empty RX buffer for receiving */
+       case AUDIOIOC_DEQUEUEBUFFER: {
+               audvdbg("AUDIOIOC_DEQUEUEBUFFER, arg - %ld\n", arg);
+               bufdesc = (FAR struct audio_buf_desc_s *)arg;
+
+               /* Try to allocate needed buffers and enqueue in receive queue */
+               while (priv->rx_cnt < CONFIG_AUDIO_I2SCHAR_NRXBUF) {
+
+                       if (bufdesc->numbytes == 0) {
+                               bufdesc->numbytes = 1024 * 16;
+                       }
+
+                       bufdesc->u.ppBuffer = &apb;
+                       ret = apb_alloc(bufdesc);
+
+                       if (ret < 0) {
+                               break;
+                       }
+
+                       ret = I2S_RECEIVE(priv->i2s, apb, alc5658char_rxcallback, priv, CONFIG_AUDIO_I2SCHAR_RXTIMEOUT);
+
+                       if (ret < 0) {
+                               apb_free(apb);
+                               break;
+                       }
+                       /* Increment counter of allocated RX buffers */
+                       sem_wait(&priv->rxsem);
+                       priv->rx_cnt++;
+                       sem_post(&priv->rxsem);
+               }
+
+               /* Clean buffer pointer to prevent wrong accesses */
+               bufdesc->u.ppBuffer = NULL;
+
+               /* We didn't hit any error before, so try to read any data from rx queue */
+               if (ret >= 0) {
+                       /* Will be blocked here if no data is available to read yet */
+                       sem_wait(&priv->cnt_rxsem);
+
+                       /* we have some data, read ... */
+                       sem_wait(&priv->rxsem);
+                       apb = (FAR struct ap_buffer_s *)dq_remfirst(&priv->rxedq);
+                       sem_post(&priv->rxsem);
+
+                       bufdesc->u.pBuffer = apb;
+                       ret = 0;
+               }
+               break;
+       }
+       break;
+
+       case AUDIOIOC_CONFIGURE: {
+               audvdbg("AUDIOIOC_CONFIGURE, arg - %ld\n", arg);
+               ret = alc5658char_configure(priv, (FAR const struct audio_caps_s *)arg);
+       }
+       break;
+
+       case AUDIOIOC_START: {
+               audvdbg("AUDIOIOC_START, arg - %ld\n", arg);
+               ret = alc5658char_start(priv, (FAR const struct audio_caps_s *)arg);
+       }
+       break;
+
+       case AUDIOIOC_STOP: {
+               audvdbg("AUDIOIOC_STOP, arg - %ld\n", arg);
+               ret = alc5658char_stop(priv, (FAR const struct audio_caps_s *)arg);
+       }
+       break;
+
+       default:
+               audvdbg("NOT SUPPORTED COMMAND %X, arg - %ld\n", cmd, arg);
+       }
+
+       return ret;
+
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: alc5658char_register
+ *
+ * Description:
+ *   Create and register the I2S character driver.
+ *
+ *   The I2S character driver is a simple character driver that supports I2S
+ *   transfers via a read() and write().  The intent of this driver is to
+ *   support I2S testing.  It is not an audio driver but does conform to some
+ *   of the buffer management heuristics of an audio driver.  It is not
+ *   suitable for use in any real driver application in its current form.
+ *
+ * Input Parameters:
+ *   i2s - An instance of the lower half I2S driver
+ *   minor - The device minor number.  The I2S character device will be
+ *     registers as /dev/alc5658charN where N is the minor number
+ *
+ * Returned Value:
+ *   OK if the driver was successfully register; A negated errno value is
+ *   returned on any failure.
+ *
+ ****************************************************************************/
+
+int alc5658char_register(FAR struct i2s_dev_s *i2s, FAR struct i2c_dev_s *i2c, FAR struct i2c_config_s *i2c_config, int minor)
+{
+       FAR struct alc5658char_dev_s *priv;
+       char devname[DEVNAME_FMTLEN];
+       int ret;
+
+       /* Sanity check */
+
+       DEBUGASSERT(i2s != NULL && i2c != NULL && (unsigned)minor < 1000);
+
+       /* Allocate a I2S character device structure */
+
+       priv = (FAR struct alc5658char_dev_s *)kmm_zalloc(sizeof(struct alc5658char_dev_s));
+       if (priv) {
+               /* Initialize the I2S character device structure */
+
+               priv->i2s = i2s;
+               priv->i2c = i2c;
+               priv->i2c_config = i2c_config;
+
+               sem_init(&priv->exclsem, 0, 1);
+
+               sem_init(&priv->alloc, 0, CONFIG_AUDIO_I2SCHAR_NTXBUF);
+
+               dq_init(&priv->rxedq);  /* Queue of received audio IN buffers */
+               sem_init(&priv->rxsem, 0, 1);   /* Protect dq */
+               sem_init(&priv->cnt_rxsem, 0, 0);       /* Assume we did not receive anything yet!!! */
+               priv->rx_cnt = 0;               /* Count allocated RX buffers */
+
+               /* Create the character device name */
+               snprintf(devname, DEVNAME_FMTLEN, DEVNAME_FMT, minor);
+               ret = register_driver(devname, &alc5658char_fops, 0666, priv);
+               if (ret < 0) {
+                       /* Free the device structure if we failed to create the character
+                        * device.
+                        */
+
+                       kmm_free(priv);
+               }
+
+               /* Init codec here only once */
+               alc5658char_i2c_script(priv, codec_init_script, sizeof(codec_init_script) / sizeof(t_codec_init_script_entry));
+
+               /* Return the result of the registration */
+
+               return OK;
+       }
+
+       return -ENOMEM;
+}
diff --git a/os/drivers/audio/alc5658char.h b/os/drivers/audio/alc5658char.h
new file mode 100644 (file)
index 0000000..67a8c5d
--- /dev/null
@@ -0,0 +1,577 @@
+/****************************************************************************
+ *
+ * Copyright 2016 Samsung Electronics All Rights Reserved.
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ * http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing,
+ * software distributed under the License is distributed on an
+ * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND,
+ * either express or implied. See the License for the specific
+ * language governing permissions and limitations under the License.
+ *
+ ****************************************************************************/
+/****************************************************************************
+ * drivers/audio/alc5658char.h
+ *
+ *   Copyright (C) 2014 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.
+ *
+ ****************************************************************************/
+
+#ifndef __DRIVERS_AUDIO_ALC5658CHAR_H
+#define __DRIVERS_AUDIO_ALC5658CHAR_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <tinyara/config.h>
+#include <tinyara/compiler.h>
+
+#include <pthread.h>
+#include <mqueue.h>
+
+#include <tinyara/wqueue.h>
+#include <tinyara/fs/ioctl.h>
+
+#ifdef CONFIG_AUDIO
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Registers Addresses ******************************************************/
+
+typedef enum {
+       ACL5658_RESET = 0x0000,
+       ACL5658_SPO_VOL = 0x0001,
+       ACL5658_HPOUT_MUTE = 0x0002,
+       ACL5658_LOUT_CTRL1 = 0x0003,
+       ACL5658_LOUT_CTRL2 = 0x0004,
+       ACL5658_HPOUT_VLML = 0x0005,
+       ACL5658_HPOUT_VLMR = 0x0006,
+       ACL5658_SPDIF_CTRL1 = 0x0008,
+       ACL5658_SPDIF_CTRL2 = 0x0009,
+       ACL5658_SPDIF_CTRL3 = 0x0036,
+       ACL5658_IN1_CTRL = 0x000C,
+       ACL5658_INL_VLM = 0x000F,
+       ACL5658_SIDETONE = 0x0018,
+       /* DIGITAL Volume */
+       ACL5658_DAC_L1R1_VLM = 0x0019,
+       ACL5658_DAC_L2R2_VLM = 0x001A,
+       ACL5658_DAC_L2R2_MUTE = 0x001B,
+       /* DIGITAL Mixers */
+       ALC5658_ADC_STR1_MXR = 0x0026,
+       ALC5658_ADC_MONO_MXR = 0x0027,
+       ACL5658_ADC_2_DAC_MXR = 0x0029,
+       ACL5658_DAC_STR_MXR = 0x002A,
+       ACL5658_DAC_MONO_MXR = 0x002B,
+       ACL5658_DAC_LB_SDTONE = 0x002C,
+       ACL5658_COPY_MODE = 0x002F,
+       /* Analog DAC Source */
+       ACL5658_DAC_SRC = 0x002D,
+       ACL5658_RECMIX1L_CTRL_1 = 0x003B,
+       ACL5658_RECMIX1L_CTRL_2 = 0x003C,
+       ACL5658_RECMIX1R_CTRL_1 = 0x003D,
+       ACL5658_RECMIX1R_CTRL_2 = 0x003E,
+       /* ANALOG Mixers */
+       ACL5658_SPKMIXL = 0x0046,
+       ACL5658_SPKMIXR = 0x0047,
+       ACL5658_SPOMIX = 0x0048,
+       ACL5658_OUTMIXL1 = 0x004D,
+       ACL5658_OUTMIXL2 = 0x004E,
+       ACL5658_OUTMIXR1 = 0x004F,
+       ACL5658_OUTMIXR2 = 0x0050,
+       ACL5658_LOUTMIX = 0x0052,
+       /* Power management */
+       ACL5658_PWR_MNG1 = 0x0061,
+       ACL5658_PWR_MNG2 = 0x0062,
+       ACL5658_PWR_MNG3 = 0x0063,
+       ACL5658_PWR_MNG4 = 0x0064,
+       ACL5658_PWR_MNG5 = 0x0065,
+       ACL5658_PWR_MNG6 = 0x0066,
+       ACL5658_PWR_MNG7 = 0x0067,
+       /* DIGITAL ports control */
+       ACL5658_IF_DTCT = 0x006B,
+       ALC5658_006E = 0x006E,
+       ALC5658_006F = 0x006F,
+       ACL5658_I2S1_CTRL = 0x0070,
+       ACL5658_I2S2_CTRL = 0x0071,
+       ACL5658_ADDA_CLK = 0x0073,
+       ACL5658_ADDA_HPF = 0x0074,
+       ALC5658_007B = 0x007B,
+       /* TDM */
+       ACL5658_TDM_CTRL1 = 0x0077,
+       ACL5658_TDM_CTRL2 = 0x0078,
+       ACL5658_TDM_CTRL3 = 0x0079,
+       ACL5658_TDM_CTRL4 = 0x007A,
+       /* Global Clock */
+       ACL5658_GLBL_CLK = 0x0080,
+       ACL5658_GLBL_PLL1 = 0x0081,
+       ACL5658_GLBL_PLL2 = 0x0082,
+       ACL5658_GLBL_ASRC1 = 0x0083,
+       ACL5658_GLBL_ASRC2 = 0x0084,
+       ACL5658_GLBL_ASRC3 = 0x0085,
+       ACL5658_GLBL_ASRC4 = 0x008A,
+       /* Amplifiers */
+       ACL5658_HP_AMP = 0x008E,
+       ACL5658_SPK_AMP = 0x00A0,
+       ALC5658_0091 = 0x0091,
+       ALC5658_INTCLK_CTRL = 0x0094,
+       ALC5658_GNRL_CTRL = 0x00FA,
+       ALC5658_GNRL_CTRL2 = 0x00FB,
+       ALC5658_0111 = 0x0111,
+       ALC5658_0125 = 0x0125,
+       ALC5658_ADDA_RST1 = 0x013A,
+       ALC5658_ADDA_RST2 = 0x013B,
+       ALC5658_0x013C = 0x013C,
+       ALC5658_NOISE_G_M1_CTRL1 = 0x0015,
+       ALC5658_NOISE_G_M2_CTRL = 0x0160,
+       ALC5658_0x01DE = 0x01DE,
+       ALC5658_0x01DF = 0x01DF,
+       ALC5658_0x01E4 = 0x01E4,
+       ALC5658_0040 = 0x0040,
+       ALC5658_0010 = 0x0010,
+} ALC5658_REG;
+
+typedef struct {
+       ALC5658_REG addr;
+       uint16_t val;
+       unsigned int delay;
+} t_codec_init_script_entry;
+
+typedef struct {
+       ALC5658_REG addr;
+       char *name;
+} t_codec_dump_entry;
+
+t_codec_init_script_entry codec_reset_script[] = {
+       {ACL5658_RESET, 0x0000, 0},     /* Reset */
+};
+
+t_codec_init_script_entry codec_stop_script[] = {
+       {ACL5658_RESET, 0x0000, 0},     /* Reset */
+       {ACL5658_I2S1_CTRL, 0x8000, 0}, /* Switch into slave to stop data transfer */
+};
+
+t_codec_init_script_entry codec_init_script[] = {
+       {ACL5658_RESET, 0x0000, 0},     /* Reset */
+       {ALC5658_006E, 0xFFFF, 0},      /* NO INFO IN DOCUMENTATION!!! */
+       {ALC5658_006F, 0xFFFF, 0},      /* NO INFO IN DOCUMENTATION!!! */
+       {ACL5658_GLBL_CLK, 0x8000, 0},  /* RC CLK, No dividers */
+       {ALC5658_INTCLK_CTRL, 0x0280, 0},       /* ??? Enable ALL int CLK, even more than in documentation */
+       {ALC5658_0111, 0xA502, 0},      /* NO INFO IN DOCUMENTATION!!! */
+       {ALC5658_0125, 0x0430, 0},      /* NO INFO IN DOCUMENTATION!!! */
+       {ALC5658_ADDA_RST1, 0x3020, 0}, /* ??? DAC1, DAC2 + alpha clock enable */
+       {ACL5658_ADDA_CLK, 0x1770, 0},  /* I2Sprediv1 = 2, bclk_ms2 = 16bits(32FS), I2Sprediv2 = 7, something reserved, dac/adc 128Fs */
+       {ACL5658_I2S1_CTRL, 0x0000, 0}, /* Master, off/normal/I2S...  16bit */
+       {ALC5658_007B, 0x0003, 0},      /* Select 64*FS for BCLK in master mode, No Info in documentation  */
+       {ALC5658_GNRL_CTRL, 0x0001, 0}, /* Enable Gate mode, Use(pass) Noise Gain Mode2 CTRL */
+       {ALC5658_0091, 0x0C16, 0},      /* NO INFO IN DOCUMENTATION!!! */
+       {ACL5658_PWR_MNG3, 0xA23E, 60}, /* VREF1 on, fast VREF1, VREF2 on, fast VREF2, MBIAS on, LOUT off, MBIAS bandgap off, HP L/R ON, HPamp x5, LDO1 out 1.2V */
+       {ACL5658_PWR_MNG3, 0xF23E, 50}, /* VREF1 on, SLOW VREF1, VREF2 on, SLOW VREF2, MBIAS on, LOUT off, MBIAS bandgap off, HP L/R ON, HPamp x5, LDO1 out 1.2V */
+       {ACL5658_PWR_MNG2, 0x0400, 50}, /* pow_dac_stereo1_filter ON */
+       {ACL5658_PWR_MNG1, 0x8080, 10}, /* en_i2s1, Pow_ldo_dacref ON */
+       {ACL5658_ADC_2_DAC_MXR, 0x8080, 0},     /* Mu_stereo1_adc_mixer_l/r MUTE */
+       {ACL5658_DAC_STR_MXR, 0xAAAA, 0},       /* Default, mute all */
+       {ACL5658_DAC_SRC, 0x0000, 0},   /* Default, no mixers (direct) */
+       {ACL5658_HP_AMP, 0x0009, 50},   /* en_out_hp - OFF, pow_pump_hp - ON, pow_capless - ON */
+       {ACL5658_PWR_MNG1, 0x8C80, 50}, /* en_i2s1, pow_dac1_l/r, Pow_ldo_dacref - ON */
+       {ALC5658_0091, 0x0E16, 50},     /* NO INFO IN DOCUMENTATION!!! */
+       {ALC5658_0040, 0x0505, 0},      /* NO INFO IN DOCUMENTATION!!! */
+       {ACL5658_PWR_MNG5, 0x0180, 0},  /* Does not match with documentation */
+       {ALC5658_0x013C, 0x3C05, 0},    /* NO INFO IN DOCUMENTATION!!! */
+       {ALC5658_0x01DF, 0x02C1, 0},    /* NO INFO IN DOCUMENTATION!!! */
+       {ALC5658_0x01DF, 0x2CC1, 0},    /* NO INFO IN DOCUMENTATION!!! */
+       {ALC5658_0x01DE, 0x5100, 0},    /* NO INFO IN DOCUMENTATION!!! */
+       {ALC5658_0x01E4, 0x0014, 0},    /* NO INFO IN DOCUMENTATION!!! */
+       {ALC5658_0x01DE, 0xD100, 30},   /* NO INFO IN DOCUMENTATION!!! */
+       {ALC5658_0x01DF, 0x2CC1, 0},    /* NO INFO IN DOCUMENTATION!!! */
+       {ALC5658_0x01DE, 0x4900, 0},    /* NO INFO IN DOCUMENTATION!!! */
+       {ALC5658_0x01E4, 0x0016, 0},    /* NO INFO IN DOCUMENTATION!!! */
+       {ALC5658_0x01DE, 0xC900, 250},  /* NO INFO IN DOCUMENTATION!!! */
+       {ALC5658_0x01DF, 0x2CC1, 0},    /* NO INFO IN DOCUMENTATION!!! */
+       {ACL5658_HPOUT_MUTE, 0x0000, 0},        /* UNMUTE HP Output */
+       {ALC5658_0x01DE, 0x4500, 0},    /* NO INFO IN DOCUMENTATION!!! */
+       {ALC5658_0x01E4, 0x001F, 0},    /* NO INFO IN DOCUMENTATION!!! */
+       {ALC5658_0x01DE, 0xC500, 800},  /* NO INFO IN DOCUMENTATION!!! */
+       {ALC5658_0040, 0x0808, 0},      /* NO INFO IN DOCUMENTATION!!! */
+       {ACL5658_PWR_MNG5, 0x0000, 0},  /* Default, PLL, LDO2, Speaker VDD off */
+       {ALC5658_0x013C, 0x2005, 0},    /* NO INFO IN DOCUMENTATION!!! */
+       {ALC5658_0x01E4, 0x0000, 0},    /* NO INFO IN DOCUMENTATION!!! */
+       {ALC5658_0x01DF, 0x20C0, 0},    /* NO INFO IN DOCUMENTATION!!! */
+       {ACL5658_ADDA_CLK, 0x0770, 0},  /* I2Sprediv1 = 2, bclk_ms2 = 16bits(32FS), I2Sprediv2 = 7, something reserved, dac/adc 128Fs */
+       {ACL5658_GLBL_CLK, 0x0000, 0},  /* MCLK, No dividers */
+       {ALC5658_NOISE_G_M2_CTRL, 0x8EC0, 0},   /* Stereo_noise_gate_mode2_en - ENABLE */
+       {ACL5658_HP_AMP, 0x0019, 0},    /* en_out_hp - ON, pow_pump_hp - ON, pow_capless - ON  */
+       {ALC5658_NOISE_G_M1_CTRL1, 0xC0F0, 0},  /* Noise_gate_mode1_en, Noise_gate_mode1_auto_en - EN, Noise_gate_mode1_threshold -78dB, DOES NOT MATCH WITH DOCUMENTATION !!! */
+       {ALC5658_NOISE_G_M1_CTRL1, 0x87F9, 0},  /* Blah blah blah, eventually enable Noise gate function >:( */
+       {ALC5658_INTCLK_CTRL, 0x0180, 0},       /* Probably enable Pow_int_clk1/2, does not match with DOC !!! */
+       {ALC5658_GNRL_CTRL2, 0x3000, 0},        /* Noise_gate_mode1/2_hp enable, DOES NOT MATCH WITH DOCUMENTATION */
+};
+
+t_codec_init_script_entry codec_initial_script[] = {
+       {ACL5658_RESET, 0x0000, 0},
+       {ALC5658_0111, 0xA502, 0},
+       {ALC5658_ADDA_RST1, 0x3030, 0}, /* ??? DAC1, DAC2 + alpha clock enable */
+       {ALC5658_006E, 0xEF00, 0},
+       {ALC5658_006F, 0xEFFC, 0},
+       {ALC5658_INTCLK_CTRL, 0x0280, 0},       /* ??? Enable ALL int CLK, even more than in documentation */
+       {ACL5658_GLBL_CLK, 0x8000, 0},  /* RC CLK, No dividers */
+       {ACL5658_I2S1_CTRL, 0x0000, 0}, /* Master, off/normal/I2S...  16bit */
+       {ACL5658_ADDA_CLK, 0x1770, 0},  /* I2Sprediv1 = 2, bclk_ms2 = 16bits(32FS), I2Sprediv2 = 7, something reserved, dac/adc 128Fs */
+       {ALC5658_0091, 0x0C16, 0},
+       {ACL5658_PWR_MNG3, 0xAA7E, 60}, /* VREF1 on, fast VREF1, VREF2 on, fast VREF2, MBIAS on, LOUT off, MBIAS bandgap off, HP L/R ON, HPamp x5, LDO1 out 1.2V */
+       {ACL5658_PWR_MNG3, 0xFE7E, 50}, /* VREF1 on, SLOW VREF1, VREF2 on, SLOW VREF2, MBIAS on, LOUT off, MBIAS bandgap off, HP L/R ON, HPamp x5, LDO1 out 1.2V */
+       {ACL5658_PWR_MNG5, 0x0004, 0},  /* LDO2 ON */
+       {ACL5658_PWR_MNG2, 0x0400, 50}, /* pow_dac_stereo1_filter ON */
+       {ACL5658_PWR_MNG1, 0x0080, 10}, /* Pow_ldo_dacref ON */
+       {ACL5658_ADC_2_DAC_MXR, 0x8080, 0},     /* Mu_stereo1_adc_mixer_l/r MUTE */
+       {ACL5658_DAC_STR_MXR, 0xAAAA, 0},       /* Default, mute all */
+       {ACL5658_DAC_SRC, 0x0000, 0},   /* Default, no mixers (direct) */
+       {ACL5658_HP_AMP, 0x0009, 50},   /* en_out_hp - OFF, pow_pump_hp - ON, pow_capless - ON */
+       {ACL5658_PWR_MNG1, 0x0F80, 50}, /* pow_dac1_l/r, pow_dac2_l/r, Pow_ldo_dacref - ON */
+       {ALC5658_0091, 0x0E16, 50},
+       {ALC5658_0040, 0x0505, 0},
+       {ACL5658_PWR_MNG5, 0x0184, 0},  /* ???NonDescribed,  LDO2 ON */
+       {ALC5658_0x013C, 0x3C05, 0},
+       {ALC5658_0x01DF, 0x2cc1, 6},
+       {ALC5658_0x01DE, 0x5100, 6},
+       {ALC5658_0x01E4, 0x0014, 6},
+       {ALC5658_0x01DE, 0xd100, 30},
+       {ALC5658_0x01DF, 0x20C1, 0},
+       {ALC5658_0x01DF, 0x2CC1, 0},
+       {ALC5658_0x01DE, 0x4900, 0},
+       {ALC5658_0x01E4, 0x0016, 0},
+       {ALC5658_0x01DE, 0xC900, 250},
+       {ALC5658_0x01DF, 0x2CC1, 0},
+       {ACL5658_HPOUT_MUTE, 0x0000, 0},        /* UNMUTE HP Output */
+       {ALC5658_0x01DE, 0x4500, 0},
+       {ALC5658_0x01E4, 0x001F, 0},
+       {ALC5658_0x01DE, 0xC500, 600},
+       {ALC5658_0x01E4, 0x0000, 0},
+       {ALC5658_0x01DF, 0x20C0, 0},
+       {ALC5658_0040, 0x0808, 0},
+       {ACL5658_PWR_MNG5, 0x0000, 0},  /* LDO2 OFF */
+       {ALC5658_0x013C, 0x2005, 0},
+       {ACL5658_PWR_MNG6, 0x0000, 0},  /* MIXERs OFF */
+       {ACL5658_PWR_MNG7, 0x0000, 0},  /* VOL Out/In ctrl, MIC in det OFF */
+       {ACL5658_PWR_MNG1, 0x0000, 0},  /* I2S, DAC, ADC, SPDIFF, CLASS D OFF */
+       {ACL5658_PWR_MNG2, 0x0000, 0},  /* Filters, PDM I/F  OFF */
+       {ACL5658_PWR_MNG3, 0x003C, 0},  /* HP L/R ON, HPamp x5, LDO1 out 0.9V */
+       {ACL5658_GLBL_CLK, 0x0000, 0},  /* MCLK, No dividers */
+       {ACL5658_ADDA_CLK, 0x0770, 0},  /* I2Sprediv1 = 2, bclk_ms2 = 16bits(32FS), I2Sprediv2 = 7, something reserved, dac/adc 128Fs */
+       {ALC5658_INTCLK_CTRL, 0x0080, 0},       /* Probably enable Pow_int_clk1/2, does not match with DOC !!! */
+};
+
+t_codec_init_script_entry codec_init_out_script[] = {
+       {ACL5658_RESET, 0x0000, 0},
+       {ALC5658_006E, 0xFFFF, 0},
+       {ALC5658_006F, 0xFFFF, 0},
+       {ALC5658_GNRL_CTRL, 0x8001, 0}, /* Bypass_noise_gate_mode2 BYPASS, digital_gate_ctrl ENABLE */
+       {ALC5658_ADDA_RST1, 0x3030, 0}, /* ??? DAC1, DAC2 + alpha clock enable */
+       {ACL5658_GLBL_PLL1, 0x0302, 0}, /* k = 2, n = 8 */
+       {ACL5658_GLBL_PLL2, 0x0800, 0}, /* m - bypass */
+       {ACL5658_ADDA_CLK, 0x1110, 0},  /* I2Sprediv1 = 2, bclk_ms2 = 16bits(32FS), I2Sprediv2 = 2, something reserved, dac/adc 128Fs */
+       {ALC5658_0091, 0x0C16, 0},
+       {ACL5658_PWR_MNG3, 0xA23E, 20}, /* VREF1 on, fast VREF1, VREF2 on, fast VREF2, MBIAS on, LOUT off, MBIAS bandgap off, HP L/R ON, HPamp x5, LDO1 out 1.2V */
+       {ACL5658_PWR_MNG3, 0xF23E, 0},  /* VREF1 on, SLOW VREF1, VREF2 on, SLOW VREF2, MBIAS on, LOUT off, MBIAS bandgap off, HP L/R ON, HPamp x5, LDO1 out 1.2V */
+       {ACL5658_PWR_MNG5, 0x0040, 0},  /* LDO2 ON */
+       {ACL5658_GLBL_CLK, 0x4000, 0},  /* PLL1, No dividers */
+       {ACL5658_GLBL_ASRC4, 0x0100, 0},        /* sel_i2s2_asrc = ASRC2 */
+       {ACL5658_GLBL_ASRC1, 0x1300, 0},        /* En_i2s2_asrc - EN, Sel_mono_dac_l/r_mode EN */
+       {ACL5658_GLBL_ASRC2, 0x0220, 0},        /* sel_da_filter_monol_track = clk_i2s2_track, sel_da_filter_monor_track = clk_i2s2_track */
+       {ACL5658_PWR_MNG1, 0xC080, 0},  /* en_i2s1/en_i2s2, Pow_ldo_dacref ON */
+       {ACL5658_HP_AMP, 0x0009, 0},    /* en_out_hp - OFF, pow_pump_hp - ON, pow_capless - ON */
+       {ACL5658_PWR_MNG1, 0xCC80, 0},  /* en_i2s1/en_i2s2, pow_dac1_l/r, Pow_ldo_dacref ON */
+       {ALC5658_0091, 0x0E16, 0},
+       {ACL5658_PWR_MNG2, 0x0700, 0},  /* pow_dac_stereo1_filter, pow_dac_monol/r_filter ON  */
+       {ACL5658_HPOUT_MUTE, 0x0000, 0},        /* OFF */
+       {ALC5658_0091, 0x0E1E, 0},
+       {ALC5658_006E, 0xFFFF, 0},
+       {ALC5658_006F, 0xFFFF, 0},
+       {ACL5658_I2S1_CTRL, 0x0000, 0}, //MASTER 32FS
+       {ACL5658_DAC_STR_MXR, 0x2A8A, 0},       /* mu_stereo_dacl1_mixl, mu_stereo_dacr1_mixr unmute */
+       {ACL5658_DAC_SRC, 0x000F, 0},   /* DAC1 stereo, DAC2 mono */
+       {ACL5658_HP_AMP, 0x0019, 0},    /* en_out_hp - ON, pow_pump_hp - ON, pow_capless - ON  */
+       {ACL5658_TDM_CTRL2, 0x000C, 0}, //loopback
+};
+
+t_codec_init_script_entry codec_init_in_script[] = {
+       {ACL5658_RESET, 0x0000, 0},
+       {ALC5658_ADDA_RST1, 0x3030, 0}, /* ??? DAC1, DAC2 + alpha clock enable */
+       {ALC5658_ADDA_RST2, 0x3030, 0}, /* ??? ADC1, ADC2 + alpha clock enable */
+       {ALC5658_006E, 0xEF00, 0},
+       {ALC5658_006F, 0xEFFC, 0},
+       {ACL5658_I2S1_CTRL, 0x0000, 0}, /* Master, off/normal/I2S...  16bit */
+       {ALC5658_GNRL_CTRL, 0x8001, 0}, /* Bypass_noise_gate_mode2 BYPASS, digital_gate_ctrl ENABLE */
+       {ACL5658_ADDA_CLK, 0x0000, 0},  /* I2Sprediv1 = 1, bclk_ms2 = 16bits(32FS), I2Sprediv2 = 1, something reserved, dac/adc 128Fs */
+       {ACL5658_PWR_MNG3, 0xA2BE, 50}, /* VREF1 on, fast VREF1, VREF2 on, fast VREF2, MBIAS on, LOUT off, MBIAS bandgap ON, HP L/R ON, HPamp x5, LDO1 out 1.2V */
+       {ACL5658_PWR_MNG3, 0xF2BE, 0},  /* VREF1 on, slow VREF1, VREF2 on, slow VREF2, MBIAS on, LOUT off, MBIAS bandgap ON, HP L/R ON, HPamp x5, LDO1 out 1.2V */
+       {ACL5658_PWR_MNG1, 0x8098, 0},  /* en_i2s1, Pow_ldo_dacref, pow_adc1_l/r ON */
+       {ACL5658_PWR_MNG1, 0x8C80, 0},  /* en_i2s1, pow_dac1_l/r Pow_ldo_dacref, pow_adc1_l/r ON */
+       {ALC5658_0091, 0x0E16, 0},
+       {ACL5658_PWR_MNG2, 0xB400, 0},  /* pow_adc_stereo1_filter, pow_adc_monol/r_filter,  pow_dac_stereo1_filter ON */
+       {ALC5658_0010, 0x3040, 0},      //CRT Mbias1 path
+       {ACL5658_PWR_MNG4, 0xC860, 0},  //enable mbias1 /* pow_bst1, pow_bst2, pow_micbias1_digital, pow_bst1-2, pow_bst2-2 ON   */
+       {ACL5658_PWR_MNG1, 0x8C98, 0},  /* en_i2s1, pow_dac1_l/r, Pow_ldo_dacref, pow_adc1_l/r ON */
+       {ACL5658_PWR_MNG6, 0x0C00, 0},  /* pow_recmix1l/r ON */
+       {ACL5658_PWR_MNG7, 0x0300, 0},  /* ?extra bits set? pow_inl_vol ON */
+       {ACL5658_IN1_CTRL, 0x3000, 0},  /* Gain -12dB + 0.75dB*0x30  */
+       {ACL5658_RECMIX1L_CTRL_2, 0x005F, 0},   /* Default, all mute */
+       {ACL5658_RECMIX1R_CTRL_2, 0x005F, 0},   /* Default, all mute */
+       {ALC5658_ADC_STR1_MXR, 0x6020, 0},      /* mu_stereo1_adcl1 unmute, sel_stereo1_adc1 Sel, mu_stereo1_adcr1 unmute */
+       {ACL5658_ADC_2_DAC_MXR, 0x0000, 100},   /* Mu_stereo1_adc_mixer_l/r unmute */
+       {ACL5658_DAC_MONO_MXR, 0x2A8A, 0},      /* mu_mono_dacl1_mixl/r unmute */
+       {ALC5658_ADC_MONO_MXR, 0x4040, 0},      /* mu_mono_adcl1 UM, sel_mono_adcl1/2 - Mono_DAC_Mixer_L, mu_mono_adcr1 UM, Sel_mono_adcr1/2 - Mono_DAC_Mixer_R, sel_mono_adcr - ADC1_L, Sel_mono_dmic_r - DMIC1_R */
+       {ACL5658_DAC_SRC, 0x000F, 0},   /* DAC1 stereo, DAC2 mono */
+       {ACL5658_TDM_CTRL1, 0x00F0, 0}, /* TDM IN/OUT 32bit LEN Applicable in master mode ??? */
+       {ACL5658_TDM_CTRL2, 0x0000, 0}, /* rx_adc_data_sel - IF_ADC1 / IF_ADC2 / DAC_REF / Null */
+};
+
+t_codec_init_script_entry codec_init_inout_script1[] = {
+       {ACL5658_RESET, 0x0000, 0},
+       {ALC5658_006E, 0xEF00, 0},
+       {ALC5658_006F, 0xEFFC, 0},
+       {ALC5658_GNRL_CTRL, 0x8001, 0},
+       {ALC5658_ADDA_RST1, 0x3030, 0},
+       {ALC5658_ADDA_RST2, 0x3030, 0},
+};
+
+t_codec_init_script_entry codec_init_pll_8K[] = {
+       {ACL5658_GLBL_PLL1, 0x0302, 0},
+       {ACL5658_GLBL_PLL2, 0x0800, 0},
+       {ACL5658_ADDA_CLK, 0x6110, 0},
+};
+
+t_codec_init_script_entry codec_init_pll_11K[] = {
+       {ACL5658_GLBL_PLL1, 0x4883, 0},
+       {ACL5658_GLBL_PLL2, 0xE000, 0},
+       {ACL5658_ADDA_CLK, 0x5110, 0},
+};
+
+t_codec_init_script_entry codec_init_pll_16K[] = {
+       {ACL5658_GLBL_PLL1, 0x0302, 0},
+       {ACL5658_GLBL_PLL2, 0x0800, 0},
+       {ACL5658_ADDA_CLK, 0x4110, 0},
+};
+
+t_codec_init_script_entry codec_init_pll_22K[] = {
+       {ACL5658_GLBL_PLL1, 0x4883, 0},
+       {ACL5658_GLBL_PLL2, 0xE000, 0},
+       {ACL5658_ADDA_CLK, 0x3110, 0},
+};
+
+t_codec_init_script_entry codec_init_pll_32K[] = {
+       {ACL5658_GLBL_PLL1, 0x0302, 0},
+       {ACL5658_GLBL_PLL2, 0x0800, 0},
+       {ACL5658_ADDA_CLK, 0x2110, 0},
+};
+
+t_codec_init_script_entry codec_init_pll_44K[] = {
+       {ACL5658_GLBL_PLL1, 0x4883, 0},
+       {ACL5658_GLBL_PLL2, 0xE000, 0},
+       {ACL5658_ADDA_CLK, 0x1110, 0},
+};
+
+t_codec_init_script_entry codec_init_pll_48K[] = {
+       {ACL5658_GLBL_PLL1, 0x0302, 0},
+       {ACL5658_GLBL_PLL2, 0x0800, 0},
+       {ACL5658_ADDA_CLK, 0x1110, 0},
+};
+
+t_codec_init_script_entry codec_init_inout_script2[] = {
+       {ALC5658_0091, 0x0C16, 0},
+       {ACL5658_PWR_MNG3, 0xA2BE, 20},
+       {ACL5658_PWR_MNG3, 0xF2BE, 0},
+       {ACL5658_PWR_MNG5, 0x0040, 0},
+       {ACL5658_GLBL_CLK, 0x4000, 0},
+       {ACL5658_GLBL_ASRC4, 0x0100, 0},
+       {ACL5658_GLBL_ASRC1, 0x1300, 0},
+       {ACL5658_GLBL_ASRC2, 0x0220, 0},
+       {ACL5658_PWR_MNG1, 0xC080, 0},
+       {ACL5658_HP_AMP, 0x0009, 0},
+       {ACL5658_PWR_MNG1, 0xCC80, 0},
+       {ACL5658_PWR_MNG1, 0xCC98, 0},
+       {ALC5658_0091, 0x0E16, 0},
+       {ACL5658_PWR_MNG2, 0xB700, 0},
+       {ACL5658_PWR_MNG4, 0xC860, 0},          //enable mbias1
+       {ACL5658_PWR_MNG6, 0x0C00, 0},
+       {ACL5658_PWR_MNG7, 0x0300, 0},
+       {ACL5658_HPOUT_MUTE, 0x8080, 0},                // MUTE OUTPUT
+       {ALC5658_0091, 0x0E1E, 0},
+       {ACL5658_I2S1_CTRL, 0x0000, 0},
+       {ACL5658_DAC_STR_MXR, 0x2A8A, 0},
+       {ACL5658_DAC_SRC, 0x000F, 0},
+       {ACL5658_HP_AMP, 0x0019, 0},
+       {ALC5658_0010, 0x3040, 0},              //CRT Mbias1 path
+       {ACL5658_IN1_CTRL, 0x0000, 0},          //BST1 gain (minimal)
+       {ACL5658_RECMIX1L_CTRL_2, 0x005F, 0},           //BST1
+       {ACL5658_RECMIX1R_CTRL_2, 0x005F, 0},           //BST1
+       {ALC5658_ADC_STR1_MXR, 0x6020, 0},
+       {ACL5658_ADC_2_DAC_MXR, 0x8080, 100},
+       {ACL5658_DAC_MONO_MXR, 0x2A8A, 0},
+       {ALC5658_ADC_MONO_MXR, 0x4040, 0},
+       {ACL5658_DAC_SRC, 0x000F, 0},
+       {ACL5658_TDM_CTRL1, 0x00F0, 0},
+       {ACL5658_TDM_CTRL2, 0x0000, 0},
+
+};
+
+t_codec_dump_entry codec_dump_script[] = {
+       {ACL5658_RESET, "ACL5658_RESET"},
+       {ACL5658_SPO_VOL, "ACL5658_SPO_VOL"},
+       {ACL5658_HPOUT_MUTE, "ACL5658_HPOUT_MUTE"},
+       {ACL5658_LOUT_CTRL1, "ACL5658_LOUT_CTRL1"},
+       {ACL5658_LOUT_CTRL2, "ACL5658_LOUT_CTRL2"},
+       {ACL5658_HPOUT_VLML, "ACL5658_HPOUT_VLML"},
+       {ACL5658_HPOUT_VLMR, "ACL5658_HPOUT_VLMR"},
+       {ACL5658_SPDIF_CTRL1, "ACL5658_SPDIF_CTRL1"},
+       {ACL5658_SPDIF_CTRL2, "ACL5658_SPDIF_CTRL2"},
+       {ACL5658_SPDIF_CTRL3, "ACL5658_SPDIF_CTRL3"},
+       {ACL5658_IN1_CTRL, "ACL5658_IN1_CTRL"},
+       {ACL5658_INL_VLM, "ACL5658_INL_VLM"},
+       {ACL5658_SIDETONE, "ACL5658_SIDETONE"},
+       {ACL5658_DAC_L1R1_VLM, "ACL5658_DAC_L1R1_VLM"},
+       {ACL5658_DAC_L2R2_VLM, "ACL5658_DAC_L2R2_VLM"},
+       {ACL5658_DAC_L2R2_MUTE, "ACL5658_DAC_L2R2_MUTE"},
+       {ALC5658_ADC_STR1_MXR, "ALC5658_ADC_STR1_MXR"},
+       {ALC5658_ADC_MONO_MXR, "ALC5658_ADC_MONO_MXR"},
+       {ACL5658_ADC_2_DAC_MXR, "ACL5658_ADC_2_DAC_MXR"},
+       {ACL5658_DAC_STR_MXR, "ACL5658_DAC_STR_MXR"},
+       {ACL5658_DAC_MONO_MXR, "ACL5658_DAC_MONO_MXR"},
+       {ACL5658_DAC_LB_SDTONE, "ACL5658_DAC_LB_SDTONE"},
+       {ACL5658_COPY_MODE, "ACL5658_COPY_MODE"},
+       {ACL5658_DAC_SRC, "ACL5658_DAC_SRC"},
+       {ACL5658_RECMIX1L_CTRL_1, "ACL5658_RECMIX1L_CTRL_1"},
+       {ACL5658_RECMIX1L_CTRL_2, "ACL5658_RECMIX1L_CTRL_2"},
+       {ACL5658_RECMIX1R_CTRL_1, "ACL5658_RECMIX1R_CTRL_1"},
+       {ACL5658_RECMIX1R_CTRL_2, "ACL5658_RECMIX1R_CTRL_2"},
+       {ACL5658_SPKMIXL, "ACL5658_SPKMIXL"},
+       {ACL5658_SPKMIXR, "ACL5658_SPKMIXR"},
+       {ACL5658_SPOMIX, "ACL5658_SPOMIX"},
+       {ACL5658_OUTMIXL1, "ACL5658_OUTMIXL1"},
+       {ACL5658_OUTMIXL2, "ACL5658_OUTMIXL2"},
+       {ACL5658_OUTMIXR1, "ACL5658_OUTMIXR1"},
+       {ACL5658_OUTMIXR2, "ACL5658_OUTMIXR2"},
+       {ACL5658_LOUTMIX, "ACL5658_LOUTMIX"},
+       {ACL5658_PWR_MNG1, "ACL5658_PWR_MNG1"},
+       {ACL5658_PWR_MNG2, "ACL5658_PWR_MNG2"},
+       {ACL5658_PWR_MNG3, "ACL5658_PWR_MNG3"},
+       {ACL5658_PWR_MNG4, "ACL5658_PWR_MNG4"},
+       {ACL5658_PWR_MNG5, "ACL5658_PWR_MNG5"},
+       {ACL5658_PWR_MNG6, "ACL5658_PWR_MNG6"},
+       {ACL5658_PWR_MNG7, "ACL5658_PWR_MNG7"},
+       {ACL5658_IF_DTCT, "ACL5658_IF_DTCT"},
+       {ALC5658_006E, "ALC5658_006E"},
+       {ALC5658_006F, "ALC5658_006F"},
+       {ACL5658_I2S1_CTRL, "ACL5658_I2S1_CTRL"},
+       {ACL5658_I2S2_CTRL, "ACL5658_I2S2_CTRL"},
+       {ACL5658_ADDA_CLK, "ACL5658_ADDA_CLK"},
+       {ACL5658_ADDA_HPF, "ACL5658_ADDA_HPF"},
+       {ALC5658_007B, "ALC5658_007B"},
+       {ACL5658_TDM_CTRL1, "ACL5658_TDM_CTRL1"},
+       {ACL5658_TDM_CTRL2, "ACL5658_TDM_CTRL2"},
+       {ACL5658_TDM_CTRL3, "ACL5658_TDM_CTRL3"},
+       {ACL5658_TDM_CTRL4, "ACL5658_TDM_CTRL4"},
+       {ACL5658_GLBL_CLK, "ACL5658_GLBL_CLK"},
+       {ACL5658_GLBL_PLL1, "ACL5658_GLBL_PLL1"},
+       {ACL5658_GLBL_PLL2, "ACL5658_GLBL_PLL2"},
+       {ACL5658_GLBL_ASRC1, "ACL5658_GLBL_ASRC1"},
+       {ACL5658_GLBL_ASRC2, "ACL5658_GLBL_ASRC2"},
+       {ACL5658_GLBL_ASRC3, "ACL5658_GLBL_ASRC3"},
+       {ACL5658_GLBL_ASRC4, "ACL5658_GLBL_ASRC4"},
+       {ACL5658_HP_AMP, "ACL5658_HP_AMP"},
+       {ACL5658_SPK_AMP, "ACL5658_SPK_AMP"},
+       {ALC5658_0091, "ALC5658_0091"},
+       {ALC5658_INTCLK_CTRL, "ALC5658_INTCLK_CTRL"},
+       {ALC5658_GNRL_CTRL, "ALC5658_GNRL_CTRL"},
+       {ALC5658_GNRL_CTRL2, "ALC5658_GNRL_CTRL2"},
+       {ALC5658_0111, "ALC5658_0111"},
+       {ALC5658_0125, "ALC5658_0125"},
+       {ALC5658_ADDA_RST1, "ALC5658_ADDA_RST1"},
+       {ALC5658_ADDA_RST2, "ALC5658_ADDA_RST2"},
+       {ALC5658_0x013C, "ALC5658_0x013C"},
+       {ALC5658_NOISE_G_M1_CTRL1, "ALC5658_NOISE_G_M1_CTRL1"},
+       {ALC5658_NOISE_G_M2_CTRL, "ALC5658_NOISE_G_M2_CTRL"},
+       {ALC5658_0x01DE, "ALC5658_0x01DE"},
+       {ALC5658_0x01DF, "ALC5658_0x01DF"},
+       {ALC5658_0x01E4, "ALC5658_0x01E4"},
+       {ALC5658_0040, "ALC5658_0040"},
+       {ALC5658_0010, "ALC5658_0010"},
+};
+
+/* Commonly defined and redefined macros */
+
+#ifndef MIN
+#define MIN(a, b)                   (((a) < (b)) ? (a) : (b))
+#endif
+
+#ifndef MAX
+#define MAX(a, b)                   (((a) > (b)) ? (a) : (b))
+#endif
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#ifdef CONFIG_ALC5658CHAR_CLKDEBUG
+extern const uint8_t g_sysclk_scaleb1[ALC5658CHAR_BCLK_MAXDIV + 1];
+extern const uint8_t g_fllratio[ALC5658CHAR_NFLLRATIO];
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: alc5658char_readreg
+ *
+ * Description
+ *    Read the specified 16-bit register from the ALC5658CHAR device.
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_ALC5658CHAR_REGDUMP) || defined(CONFIG_ALC5658CHAR_CLKDEBUG)
+struct alc5658char_dev_s;
+uint16_t alc5658char_readreg(FAR struct alc5658char_dev_s *priv, uint16_t regaddr);
+#endif
+
+#endif                                                 /* CONFIG_AUDIO */
+#endif                                                 /* __DRIVERS_AUDIO_ALC5658CHAR_H */
index ca045ff..7b5f48f 100644 (file)
 #define AUDIOIOC_REGISTERMQ         _AUDIOIOC(14)
 #define AUDIOIOC_UNREGISTERMQ       _AUDIOIOC(15)
 #define AUDIOIOC_HWRESET            _AUDIOIOC(16)
+#define AUDIOIOC_DEQUEUEBUFFER      _AUDIOIOC(17)
 
 /* Audio Device Types *******************************************************/
 /* The NuttX audio interface support different types of audio devices for
 #define AUDIO_FU_UNDERFLOW          0x2000
 #define AUDIO_FU_OVERFLOW           0x4000
 #define AUDIO_FU_LATENCY            0x8000
+#define AUDIO_FU_MICGAIN            0x8001
 
 /* Processing Unit controls *************************************************/