Browse Source

[bsp][stm32f429-apollo]add audio sound and micphone driver.

EvalZero 6 years ago
parent
commit
e14b1ac055

+ 5 - 0
bsp/stm32f429-apollo/drivers/Kconfig

@@ -18,6 +18,11 @@ config RT_USING_SPI5
     bool "Enable SPI5"
     default y     
 
+config RT_USING_SAI_AUDIO
+    select RT_USING_AUDIO
+    bool "Enable AUDIO"
+    default n
+
 config RT_RTC_NAME
     string "The name of RTC device"
     default rtc

+ 14 - 4
bsp/stm32f429-apollo/drivers/SConscript

@@ -2,8 +2,12 @@ from building import *
 
 cwd = GetCurrentDir()
 
+# init src and inc vars
+src = []
+inc = []
+
 # add the general drivers.
-src = Split("""
+src += Split("""
 board.c
 stm32f4xx_it.c
 usart.c
@@ -12,6 +16,9 @@ drv_rtc.c
 drv_mpu.c
 """)
 
+# add dwin basic include
+inc += [cwd]
+
 # add sdio driver
 if GetDepend('RT_USING_DFS'):
     src += ['drv_sdio_sd.c']
@@ -39,12 +46,15 @@ if GetDepend('RT_USING_SPI'):
 if GetDepend('RT_USING_SFUD'):
     src += ['drv_spi_flash.c']
 
+# add audio drivers.
+if GetDepend('RT_USING_SAI_AUDIO'):
+    src += Glob('./audio/*.c')
+    inc += [cwd + "/audio"] 
+
 # add lcd drivers.
 if GetDepend('PKG_USING_GUIENGINE'):
     src += ['drv_lcd.c']
- 
-CPPPATH = [cwd]
 
-group = DefineGroup('Drivers', src, depend = [''], CPPPATH = CPPPATH)
+group = DefineGroup('Drivers', src, depend = [''], CPPPATH = inc)
 
 Return('group')

+ 41 - 0
bsp/stm32f429-apollo/drivers/audio/drv_audio.h

@@ -0,0 +1,41 @@
+/*
+ * Copyright (c) 2006-2018, RT-Thread Development Team
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2018-11-14     ZeroFree     first implementation
+ */
+
+#ifndef __DRV_AUDIO_H__
+#define __DRV_AUDIO_H__
+
+#include <rtthread.h>
+#include <drivers/audio.h>
+#include <audio_pipe.h>
+
+/* SAIA DMA Stream TX definitions */
+#define SAIA_TX_DMAx_CLK_ENABLE()        __HAL_RCC_DMA2_CLK_ENABLE()
+#define SAIA_TX_DMAx_CLK_DISABLE()       __HAL_RCC_DMA2_CLK_DISABLE()
+#define SAIA_TX_DMAx_STREAM              DMA2_Stream3
+#define SAIA_TX_DMAx_CHANNEL             DMA_CHANNEL_0
+#define SAIA_TX_DMAx_IRQ                 DMA2_Stream3_IRQn
+#define SAIA_TX_DMAx_PERIPH_DATA_SIZE    DMA_PDATAALIGN_HALFWORD
+#define SAIA_TX_DMAx_MEM_DATA_SIZE       DMA_MDATAALIGN_HALFWORD
+#define SAIA_TX_DMAx_IRQHandler          DMA2_Stream3_IRQHandler
+
+/* SAIB DMA Stream TX definitions */
+#define SAIA_RX_DMAx_CLK_ENABLE()        __HAL_RCC_DMA2_CLK_ENABLE()
+#define SAIA_RX_DMAx_CLK_DISABLE()       __HAL_RCC_DMA2_CLK_DISABLE()
+#define SAIA_RX_DMAx_STREAM              DMA2_Stream5
+#define SAIA_RX_DMAx_CHANNEL             DMA_CHANNEL_0
+#define SAIA_RX_DMAx_IRQ                 DMA2_Stream5_IRQn
+#define SAIA_RX_DMAx_PERIPH_DATA_SIZE    DMA_PDATAALIGN_HALFWORD
+#define SAIA_RX_DMAx_MEM_DATA_SIZE       DMA_MDATAALIGN_HALFWORD
+#define SAIA_RX_DMAx_IRQHandler          DMA2_Stream5_IRQHandler
+
+int SAIA_SampleRate_Set(uint32_t samplerate);
+int rt_hw_audio_init(char *i2c_bus_name);
+
+#endif

+ 254 - 0
bsp/stm32f429-apollo/drivers/audio/drv_mic.c

@@ -0,0 +1,254 @@
+/*
+ * Copyright (c) 2006-2018, RT-Thread Development Team
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2018-11-14     ZeroFree     first implementation
+ */
+
+#include <rtthread.h>
+#include <rthw.h>
+#include <rtdevice.h>
+
+#include <string.h>
+
+#include "drv_audio.h"
+#include "drv_wm8978.h"
+#include <stm32f4xx.h>
+
+#define DBG_ENABLE
+#define DBG_LEVEL DBG_INFO
+#define DBG_COLOR
+#define DBG_SECTION_NAME    "MIC"
+#include <rtdbg.h>
+
+struct micphone_device
+{
+    struct rt_device parent;
+    rt_uint16_t *recv_fifo;
+    struct rt_audio_pipe record_pipe;
+
+    /* i2c mode */
+    struct rt_i2c_bus_device *i2c_device;
+};
+
+#define AUDIO_RECV_BUFFER_SIZE        (2048)
+
+extern SAI_HandleTypeDef SAI1B_Handler;
+extern DMA_HandleTypeDef SAI1_RXDMA_Handler;
+extern SAI_HandleTypeDef SAI1A_Handler;
+extern DMA_HandleTypeDef SAI1_TXDMA_Handler;
+
+static struct micphone_device micphone;
+static uint16_t send_fifo[2] = {0, 0};
+
+static void SAIB_Init(void)
+{
+    HAL_SAI_DeInit(&SAI1B_Handler);
+    SAI1B_Handler.Instance = SAI1_Block_B;
+    SAI1B_Handler.Init.AudioMode = SAI_MODESLAVE_RX;
+    SAI1B_Handler.Init.Synchro = SAI_SYNCHRONOUS;
+    SAI1B_Handler.Init.OutputDrive = SAI_OUTPUTDRIVE_ENABLE;
+    SAI1B_Handler.Init.NoDivider = SAI_MASTERDIVIDER_ENABLE;
+    SAI1B_Handler.Init.FIFOThreshold = SAI_FIFOTHRESHOLD_1QF;
+    SAI1B_Handler.Init.ClockSource = SAI_CLKSOURCE_PLLI2S;
+    SAI1B_Handler.Init.MonoStereoMode = SAI_MONOMODE;
+    SAI1B_Handler.Init.Protocol = SAI_FREE_PROTOCOL;
+    SAI1B_Handler.Init.DataSize = SAI_DATASIZE_16;
+    SAI1B_Handler.Init.FirstBit = SAI_FIRSTBIT_MSB;
+    SAI1B_Handler.Init.ClockStrobing = SAI_CLOCKSTROBING_RISINGEDGE;
+
+    SAI1B_Handler.FrameInit.FrameLength = 64;
+    SAI1B_Handler.FrameInit.ActiveFrameLength = 32;
+    SAI1B_Handler.FrameInit.FSDefinition = SAI_FS_CHANNEL_IDENTIFICATION;
+    SAI1B_Handler.FrameInit.FSPolarity = SAI_FS_ACTIVE_LOW;
+    SAI1B_Handler.FrameInit.FSOffset = SAI_FS_BEFOREFIRSTBIT;
+
+    SAI1B_Handler.SlotInit.FirstBitOffset = 0;
+    SAI1B_Handler.SlotInit.SlotSize = SAI_SLOTSIZE_32B;
+    SAI1B_Handler.SlotInit.SlotNumber = 2;
+    SAI1B_Handler.SlotInit.SlotActive = SAI_SLOTACTIVE_0 | SAI_SLOTACTIVE_1;
+
+    HAL_SAI_Init(&SAI1B_Handler);
+    __HAL_SAI_ENABLE(&SAI1B_Handler);
+
+    SAIA_RX_DMAx_CLK_ENABLE();
+    __HAL_LINKDMA(&SAI1B_Handler, hdmarx, SAI1_RXDMA_Handler);
+    SAI1_RXDMA_Handler.Instance = SAIA_RX_DMAx_STREAM;
+    SAI1_RXDMA_Handler.Init.Channel = SAIA_RX_DMAx_CHANNEL;
+    SAI1_RXDMA_Handler.Init.Direction = DMA_PERIPH_TO_MEMORY;
+    SAI1_RXDMA_Handler.Init.PeriphInc = DMA_PINC_DISABLE;
+    SAI1_RXDMA_Handler.Init.MemInc = DMA_MINC_ENABLE;
+    SAI1_RXDMA_Handler.Init.PeriphDataAlignment = SAIA_RX_DMAx_PERIPH_DATA_SIZE;
+    SAI1_RXDMA_Handler.Init.MemDataAlignment = SAIA_RX_DMAx_MEM_DATA_SIZE;
+    SAI1_RXDMA_Handler.Init.Mode = DMA_CIRCULAR;
+    SAI1_RXDMA_Handler.Init.Priority = DMA_PRIORITY_MEDIUM;
+    SAI1_RXDMA_Handler.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
+    SAI1_RXDMA_Handler.Init.MemBurst = DMA_MBURST_SINGLE;
+    SAI1_RXDMA_Handler.Init.PeriphBurst = DMA_PBURST_SINGLE;
+    HAL_DMA_DeInit(&SAI1_RXDMA_Handler);
+    HAL_DMA_Init(&SAI1_RXDMA_Handler);
+
+    HAL_NVIC_SetPriority(SAIA_RX_DMAx_IRQ, 0, 1);
+    HAL_NVIC_EnableIRQ(SAIA_RX_DMAx_IRQ);
+}
+
+void SAIA_RX_DMAx_IRQHandler(void)
+{
+    HAL_DMA_IRQHandler(&SAI1_RXDMA_Handler);
+}
+
+void HAL_SAI_RxHalfCpltCallback(SAI_HandleTypeDef *hsai)
+{
+    if (hsai == &SAI1B_Handler)
+    {
+        rt_device_write(&micphone.record_pipe.parent, 0, micphone.recv_fifo, AUDIO_RECV_BUFFER_SIZE / 2);
+    }
+}
+
+void HAL_SAI_RxCpltCallback(SAI_HandleTypeDef *hsai)
+{
+    if (hsai == &SAI1B_Handler)
+    {
+        rt_device_write(&micphone.record_pipe.parent, 0, micphone.recv_fifo + (AUDIO_RECV_BUFFER_SIZE /  4), AUDIO_RECV_BUFFER_SIZE / 2);
+    }
+}
+
+static rt_err_t micphone_init(rt_device_t dev)
+{
+    SAIB_Init();
+
+    return RT_EOK;
+}
+
+static rt_err_t micphone_open(rt_device_t dev, rt_uint16_t oflag)
+{
+    struct micphone_device *mic = RT_NULL;
+
+    mic = (struct micphone_device *)dev;
+
+    if (oflag & RT_DEVICE_OFLAG_RDONLY)
+    {
+        LOG_I("Open Micphone Device!");
+
+        rt_device_open(&mic->record_pipe.parent, RT_DEVICE_OFLAG_RDONLY);
+        /* Disable DMA Interruption */
+        __HAL_DMA_DISABLE_IT(&SAI1_TXDMA_Handler, DMA_IT_TC | DMA_IT_HT);
+        HAL_DMA_Start(&SAI1_TXDMA_Handler, (uint32_t)&send_fifo[0], (uint32_t)&SAI1_Block_A->DR, 2);
+        /* Start RX DMA */
+        HAL_SAI_Receive_DMA(&SAI1B_Handler, (uint8_t *)(micphone.recv_fifo), AUDIO_RECV_BUFFER_SIZE / 2);
+    }
+
+    return RT_EOK;
+}
+
+static rt_size_t micphone_read(rt_device_t dev, rt_off_t pos,
+                               void *buffer, rt_size_t size)
+{
+    struct micphone_device *mic = RT_NULL;
+
+    mic = (struct micphone_device *)dev;
+    return rt_device_read(&mic->record_pipe.parent, pos, buffer, size);
+}
+
+static rt_err_t micphone_control(rt_device_t dev, int cmd, void *args)
+{
+    rt_err_t value, result = RT_EOK;
+
+    switch (cmd)
+    {
+    case CODEC_CMD_SET_VOLUME:
+    {
+        // TODO
+        break;
+    }
+
+    case CODEC_CMD_SAMPLERATE:
+    {
+        value = *(int *)args;
+        LOG_I("Set Samplerate %d", value);
+        result = SAIA_SampleRate_Set(value);
+        break;
+    }
+
+    default:
+        break;
+    }
+
+    return result;
+}
+
+static rt_err_t micphone_close(rt_device_t dev)
+{
+    struct micphone_device *mic = RT_NULL;
+
+    mic = (struct micphone_device *)dev;
+    HAL_SAI_DMAStop(&SAI1A_Handler);
+    HAL_SAI_DMAStop(&SAI1B_Handler);
+    rt_device_close(&mic->record_pipe.parent);
+    LOG_I("Close Micphone Device!");
+
+    return RT_EOK;
+}
+
+int rt_hw_micphone_init(char *i2c_bus_name)
+{
+    int result = RT_EOK;
+    struct micphone_device *mic = &micphone;
+
+    if (mic->recv_fifo != RT_NULL)
+    {
+        return RT_EOK;
+    }
+
+    mic->recv_fifo = rt_malloc(AUDIO_RECV_BUFFER_SIZE);
+    if (mic->recv_fifo == RT_NULL)
+    {
+        result = -RT_ENOMEM;
+        goto __exit;
+    }
+    memset(mic->recv_fifo, 0, AUDIO_RECV_BUFFER_SIZE);
+
+    mic->parent.type      = RT_Device_Class_Sound;
+    mic->parent.init      = micphone_init;
+    mic->parent.open      = micphone_open;
+    mic->parent.control   = micphone_control;
+    mic->parent.write     = RT_NULL;
+    mic->parent.read      = micphone_read;
+    mic->parent.close     = micphone_close;
+    mic->parent.user_data = mic;
+
+    /* register the device */
+    rt_device_register(&mic->parent, "mic", RT_DEVICE_FLAG_RDONLY | RT_DEVICE_FLAG_DMA_RX);
+
+    rt_device_init(&mic->parent);
+
+    {
+        rt_uint8_t *buffer = rt_malloc(AUDIO_RECV_BUFFER_SIZE);
+        if (buffer == RT_NULL)
+        {
+            result = -RT_ENOMEM;
+            goto __exit;
+        }
+        memset(buffer, 0, AUDIO_RECV_BUFFER_SIZE);
+
+        rt_audio_pipe_init(&mic->record_pipe,
+                           "voice",
+                           RT_PIPE_FLAG_FORCE_WR | RT_PIPE_FLAG_BLOCK_RD,
+                           buffer,
+                           AUDIO_RECV_BUFFER_SIZE);
+    }
+
+    return RT_EOK;
+
+__exit:
+    if (mic->recv_fifo)
+    {
+        rt_free(mic->recv_fifo);
+        mic->recv_fifo = RT_NULL;
+    }
+
+    return result;
+}

+ 594 - 0
bsp/stm32f429-apollo/drivers/audio/drv_sound.c

@@ -0,0 +1,594 @@
+/*
+ * Copyright (c) 2006-2018, RT-Thread Development Team
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2018-11-14     ZeroFree     first implementation
+ */
+
+#include <rtthread.h>
+#include <rtdevice.h>
+#include <rthw.h>
+
+#include <stdint.h>
+#include <string.h>
+
+#include "drv_audio.h"
+#include "drv_wm8978.h"
+#include <stm32f4xx.h>
+
+#define DBG_ENABLE
+#define DBG_LEVEL DBG_LOG
+#define DBG_COLOR
+#define DBG_SECTION_NAME    "Sound"
+#include <rtdbg.h>
+
+/**
+ * Audio Memory Node Manage
+ */
+struct rt_data_node
+{
+    char *data_ptr;
+    rt_uint32_t data_size;
+};
+
+struct rt_data_node_list
+{
+    struct rt_data_node *node;
+    rt_uint32_t size;
+    rt_uint32_t read_index, write_index;
+    rt_uint32_t data_offset;
+    void (*read_complete)(struct rt_data_node *node, void *user_data);
+    void *user_data;
+};
+
+int rt_data_node_init(struct rt_data_node_list **node_list, rt_uint32_t size)
+{
+    int result = RT_EOK;
+    struct rt_data_node_list *list = RT_NULL;
+    struct rt_data_node *node = RT_NULL;
+
+    list = rt_malloc(sizeof(struct rt_data_node_list));
+    if (list == RT_NULL)
+    {
+        result = -RT_ENOMEM;
+        goto __exit;
+    }
+    memset(list, 0, sizeof(struct rt_data_node_list));
+
+    node = rt_malloc(sizeof(struct rt_data_node) * size);
+    if (size == RT_NULL)
+    {
+        result = -RT_ENOMEM;
+        goto __exit;
+    }
+    memset(node, 0, sizeof(struct rt_data_node));
+
+    list->node = node;
+    list->size = size;
+    list->read_index = 0;
+    list->write_index = 0;
+    list->data_offset = 0;
+    list->read_complete = RT_NULL;
+    list->user_data = 0;
+
+    *node_list = list;
+
+    return result;
+
+__exit:
+    if (list)
+        rt_free(list);
+
+    if (node)
+        rt_free(node);
+
+    return result;
+}
+
+int rt_data_node_is_empty(struct rt_data_node_list *node_list)
+{
+    rt_uint32_t read_index, write_index;
+    rt_base_t level;
+
+    level = rt_hw_interrupt_disable();
+    read_index = node_list->read_index;
+    write_index = node_list->write_index;
+    rt_hw_interrupt_enable(level);
+
+    if (read_index == write_index)
+    {
+        return RT_TRUE;
+    }
+    else
+    {
+        return RT_FALSE;
+    }
+}
+
+void wait_node_free(struct rt_data_node_list *node_list)
+{
+    while (node_list->read_index != node_list->write_index)
+        rt_thread_mdelay(5);
+}
+
+int rt_data_node_write(struct rt_data_node_list *node_list, void *buffer, rt_uint32_t size)
+{
+    struct rt_data_node *node = RT_NULL;
+    rt_uint32_t read_index, write_index, next_index;
+    rt_base_t level;
+
+    level = rt_hw_interrupt_disable();
+    read_index = node_list->read_index;
+    write_index = node_list->write_index;
+    rt_hw_interrupt_enable(level);
+
+    next_index = write_index + 1;
+    if (next_index >= node_list->size)
+        next_index = 0;
+
+    if (next_index == read_index)
+    {
+        rt_kprintf("[node]:node list full, write index = %d, read index = %d \n", write_index, read_index);
+        return -RT_ERROR;
+    }
+
+    level = rt_hw_interrupt_disable();
+    /* set node attribute */
+    node = &node_list->node[write_index];
+    node->data_ptr = (char *) buffer;
+    node->data_size = size;
+    node_list->write_index = next_index;
+    rt_hw_interrupt_enable(level);
+
+    return size;
+}
+
+int rt_data_node_read(struct rt_data_node_list *node_list, void *buffer, rt_uint32_t size)
+{
+    struct rt_data_node *node = RT_NULL;
+    rt_uint32_t read_index, write_index, next_index;
+    rt_int32_t remain_len, copy_size;
+    rt_uint32_t read_offset, data_offset;
+    rt_base_t level;
+    rt_uint32_t result = size;
+
+    level = rt_hw_interrupt_disable();
+    read_index = node_list->read_index;
+    write_index = node_list->write_index;
+    rt_hw_interrupt_enable(level);
+
+    read_offset = 0;
+    if (read_index == write_index)
+    {
+        result = 0;
+    }
+    else
+    {
+        do
+        {
+            node = &node_list->node[node_list->read_index];
+            data_offset = node_list->data_offset;
+            remain_len = node->data_size - data_offset;
+            if (size - read_offset > remain_len)
+            {
+                /* Full*/
+                copy_size = remain_len;
+            }
+            else
+            {
+                /* reamain buffer */
+                copy_size = size - read_offset;
+            }
+
+            memcpy((char *)buffer + read_offset, node->data_ptr + data_offset, copy_size);
+            read_offset += copy_size;
+            data_offset += copy_size;
+            node_list->data_offset = data_offset;
+
+            if (data_offset >= node->data_size)
+            {
+                /* notify transmitted complete. */
+                if (node_list->read_complete != RT_NULL)
+                {
+                    node_list->read_complete(node, node_list->user_data);
+                }
+
+                level = rt_hw_interrupt_disable();
+                read_index = node_list->read_index;
+                write_index = node_list->write_index;
+                rt_hw_interrupt_enable(level);
+
+                next_index = read_index + 1;
+                if (next_index >= node_list->size)
+                    next_index = 0;
+
+                level = rt_hw_interrupt_disable();
+                node_list->read_index = next_index;
+                node_list->data_offset = 0;
+                rt_hw_interrupt_enable(level);
+
+                if (next_index == write_index)
+                {
+                    result = read_offset;
+                    break;
+                }
+            }
+        }
+        while (read_offset < size);
+    }
+
+    return result;
+}
+
+static void data_node_read_complete(struct rt_data_node *node, void *user_data)
+{
+    struct rt_device *dev = RT_NULL;
+
+    dev = (struct rt_device *)user_data;
+    if (dev->tx_complete != RT_NULL)
+    {
+        dev->tx_complete(dev, node->data_ptr);
+    }
+}
+
+/**
+ * RT-Thread Audio Device Driver
+ */
+struct sound_device
+{
+    struct rt_device parent;
+    struct rt_data_node_list *node_list;
+
+    /* i2c mode */
+    struct rt_i2c_bus_device *i2c_device;
+
+    char *send_fifo;
+};
+
+#define AUDIO_SEND_BUFFER_SIZE (2048 * 2)
+
+SAI_HandleTypeDef SAI1B_Handler;
+DMA_HandleTypeDef SAI1_RXDMA_Handler;
+SAI_HandleTypeDef SAI1A_Handler;
+DMA_HandleTypeDef SAI1_TXDMA_Handler;
+
+static struct sound_device *sound;
+
+static void SAIA_Init(void)
+{
+    HAL_SAI_DeInit(&SAI1A_Handler);
+    // SAI1A_Handler.Init.AudioFrequency = 44100;
+    SAI1A_Handler.Instance = SAI1_Block_A;
+    SAI1A_Handler.Init.AudioMode = SAI_MODEMASTER_TX;
+    SAI1A_Handler.Init.Synchro = SAI_ASYNCHRONOUS;
+    SAI1A_Handler.Init.OutputDrive = SAI_OUTPUTDRIVE_ENABLE;
+    SAI1A_Handler.Init.NoDivider = SAI_MASTERDIVIDER_ENABLE;
+    SAI1A_Handler.Init.FIFOThreshold = SAI_FIFOTHRESHOLD_EMPTY;
+    SAI1A_Handler.Init.ClockSource = SAI_CLKSOURCE_PLLI2S;
+    SAI1A_Handler.Init.MonoStereoMode = SAI_STEREOMODE;
+    SAI1A_Handler.Init.Protocol = SAI_FREE_PROTOCOL;
+    SAI1A_Handler.Init.DataSize = SAI_DATASIZE_16;
+    SAI1A_Handler.Init.FirstBit = SAI_FIRSTBIT_MSB;
+    SAI1A_Handler.Init.ClockStrobing = SAI_CLOCKSTROBING_RISINGEDGE;
+
+    SAI1A_Handler.FrameInit.FrameLength = 64;
+    SAI1A_Handler.FrameInit.ActiveFrameLength = 32;
+    SAI1A_Handler.FrameInit.FSDefinition = SAI_FS_CHANNEL_IDENTIFICATION;
+    SAI1A_Handler.FrameInit.FSPolarity = SAI_FS_ACTIVE_LOW;
+    SAI1A_Handler.FrameInit.FSOffset = SAI_FS_BEFOREFIRSTBIT;
+    SAI1A_Handler.SlotInit.FirstBitOffset = 0;
+    SAI1A_Handler.SlotInit.SlotSize = SAI_SLOTSIZE_32B;
+    SAI1A_Handler.SlotInit.SlotNumber = 2;
+    SAI1A_Handler.SlotInit.SlotActive = SAI_SLOTACTIVE_0 | SAI_SLOTACTIVE_1;
+
+    HAL_SAI_Init(&SAI1A_Handler);
+    __HAL_SAI_ENABLE(&SAI1A_Handler);
+
+    /* DMA Configuration */
+    SAIA_TX_DMAx_CLK_ENABLE();
+    __HAL_LINKDMA(&SAI1A_Handler, hdmatx, SAI1_TXDMA_Handler);
+    SAI1_TXDMA_Handler.Instance = SAIA_TX_DMAx_STREAM;
+    SAI1_TXDMA_Handler.Init.Channel = SAIA_TX_DMAx_CHANNEL;
+    SAI1_TXDMA_Handler.Init.Direction = DMA_MEMORY_TO_PERIPH;
+    SAI1_TXDMA_Handler.Init.PeriphInc = DMA_PINC_DISABLE;
+    SAI1_TXDMA_Handler.Init.MemInc = DMA_MINC_ENABLE;
+    SAI1_TXDMA_Handler.Init.PeriphDataAlignment = SAIA_TX_DMAx_PERIPH_DATA_SIZE;
+    SAI1_TXDMA_Handler.Init.MemDataAlignment = SAIA_TX_DMAx_MEM_DATA_SIZE;
+    SAI1_TXDMA_Handler.Init.Mode = DMA_CIRCULAR;
+    SAI1_TXDMA_Handler.Init.Priority = DMA_PRIORITY_HIGH;
+    SAI1_TXDMA_Handler.Init.FIFOMode = DMA_FIFOMODE_ENABLE;
+    SAI1_TXDMA_Handler.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
+    SAI1_TXDMA_Handler.Init.MemBurst = DMA_MBURST_SINGLE;
+    SAI1_TXDMA_Handler.Init.PeriphBurst = DMA_PBURST_SINGLE;
+    HAL_DMA_DeInit(&SAI1_TXDMA_Handler);
+    HAL_DMA_Init(&SAI1_TXDMA_Handler);
+
+    HAL_NVIC_SetPriority(SAIA_TX_DMAx_IRQ, 0, 0);
+    HAL_NVIC_EnableIRQ(SAIA_TX_DMAx_IRQ);
+}
+
+const uint16_t SAI_PSC_TBL[][5] =
+{
+    {800, 344, 7, 0, 12},
+    {1102, 429, 2, 18, 2},
+    {1600, 344, 7, 0, 6},
+    {2205, 429, 2, 18, 1},
+    {3200, 344, 7, 0, 3},
+    {4410, 429, 2, 18, 0},
+    {4800, 344, 7, 0, 2},
+    {8820, 271, 2, 2, 1},
+    {9600, 344, 7, 0, 1},
+    {17640, 271, 2, 2, 0},
+    {19200, 344, 7, 0, 0},
+};
+
+void SAIA_DMA_Enable(void)
+{
+    SAI1_Block_A->CR1 |= SAI_xCR1_DMAEN;
+}
+
+void SAIA_DMA_Disable(void)
+{
+    SAI1_Block_A->CR1 &= ~SAI_xCR1_DMAEN;
+}
+
+int SAIA_SampleRate_Set(uint32_t samplerate)
+{
+    uint16_t i = 0;
+
+    RCC_PeriphCLKInitTypeDef RCCSAI1_Sture;
+    for (i = 0; i < (sizeof(SAI_PSC_TBL) / 10); i++)
+    {
+        if ((samplerate / 10) == SAI_PSC_TBL[i][0])
+            break;
+    }
+    if (i == (sizeof(SAI_PSC_TBL) / 10))
+        return -RT_ERROR;
+    RCCSAI1_Sture.PeriphClockSelection = RCC_PERIPHCLK_SAI_PLLI2S;
+    RCCSAI1_Sture.PLLI2S.PLLI2SN = (uint32_t)SAI_PSC_TBL[i][1];
+    RCCSAI1_Sture.PLLI2S.PLLI2SQ = (uint32_t)SAI_PSC_TBL[i][2];
+    RCCSAI1_Sture.PLLI2SDivQ = SAI_PSC_TBL[i][3] + 1;
+    HAL_RCCEx_PeriphCLKConfig(&RCCSAI1_Sture);
+
+    __HAL_RCC_SAI_BLOCKACLKSOURCE_CONFIG(RCC_SAIACLKSOURCE_PLLI2S);
+
+    __HAL_SAI_DISABLE(&SAI1A_Handler);
+    SAIA_DMA_Disable();
+    SAI1A_Handler.Init.AudioFrequency = samplerate;
+    HAL_SAI_Init(&SAI1A_Handler);
+    SAIA_DMA_Enable();
+    __HAL_SAI_ENABLE(&SAI1A_Handler);
+
+    return RT_EOK;
+}
+
+void HAL_SAI_MspInit(SAI_HandleTypeDef *hsai)
+{
+    GPIO_InitTypeDef GPIO_Initure;
+    __HAL_RCC_SAI1_CLK_ENABLE();
+    __HAL_RCC_GPIOE_CLK_ENABLE();
+
+    GPIO_Initure.Pin = GPIO_PIN_2 | GPIO_PIN_3 | GPIO_PIN_4 | GPIO_PIN_5 | GPIO_PIN_6;
+    GPIO_Initure.Mode = GPIO_MODE_AF_PP;
+    GPIO_Initure.Pull = GPIO_PULLUP;
+    GPIO_Initure.Speed = GPIO_SPEED_HIGH;
+    GPIO_Initure.Alternate = GPIO_AF6_SAI1;
+    HAL_GPIO_Init(GPIOE, &GPIO_Initure);
+}
+
+void SAIA_TX_DMAx_IRQHandler(void)
+{
+    HAL_DMA_IRQHandler(&SAI1_TXDMA_Handler);
+}
+
+void HAL_SAI_TxHalfCpltCallback(SAI_HandleTypeDef *hsai)
+{
+    int result;
+    struct sound_device *snd = sound;
+
+    if (hsai == &SAI1A_Handler)
+    {
+        result = rt_data_node_is_empty(snd->node_list);
+        if (result)
+        {
+            rt_kprintf("# ");
+            memset(snd->send_fifo, 0, AUDIO_SEND_BUFFER_SIZE / 2);
+        }
+        else
+        {
+            memset(snd->send_fifo, 0, AUDIO_SEND_BUFFER_SIZE / 2);
+            rt_data_node_read(snd->node_list, snd->send_fifo, AUDIO_SEND_BUFFER_SIZE / 2);
+        }
+    }
+}
+
+void HAL_SAI_TxCpltCallback(SAI_HandleTypeDef *hsai)
+{
+    int result;
+    struct sound_device *snd = sound;
+
+    if (hsai == &SAI1A_Handler)
+    {
+        result = rt_data_node_is_empty(snd->node_list);
+        if (result)
+        {
+            rt_kprintf("* ");
+            memset(snd->send_fifo + (AUDIO_SEND_BUFFER_SIZE / 2), 0, AUDIO_SEND_BUFFER_SIZE / 2);
+        }
+        else
+        {
+            memset(snd->send_fifo + (AUDIO_SEND_BUFFER_SIZE / 2), 0, AUDIO_SEND_BUFFER_SIZE / 2);
+            rt_data_node_read(snd->node_list, snd->send_fifo + (AUDIO_SEND_BUFFER_SIZE / 2), AUDIO_SEND_BUFFER_SIZE / 2);
+        }
+
+    }
+}
+
+void HAL_SAI_ErrorCallback(SAI_HandleTypeDef *hsai)
+{
+    rt_kprintf("x ");
+}
+
+
+static rt_err_t sound_init(rt_device_t dev)
+{
+    int result;
+    struct sound_device *snd = (struct sound_device *)dev;
+
+    SAIA_Init();
+    result = wm8978_init(snd->i2c_device);
+
+    return result;
+}
+
+static rt_err_t sound_open(rt_device_t dev, rt_uint16_t oflag)
+{
+    int result = RT_EOK;
+    struct sound_device *snd = (struct sound_device *)dev;
+
+    LOG_I("Open Sound Device!");
+
+    /* Configure DMA transmit */
+    result = HAL_SAI_Transmit_DMA(&SAI1A_Handler, (uint8_t *)(snd->send_fifo), AUDIO_SEND_BUFFER_SIZE / 2);
+    if (result != HAL_OK)
+    {
+        LOG_E("Start DMA Transmit Failed!");
+        result = -RT_ERROR;
+    }
+
+    return result;
+}
+
+static rt_err_t sound_control(rt_device_t dev, int cmd, void *args)
+{
+    int value, result = RT_EOK;
+    struct sound_device *snd = (struct sound_device *)dev;
+
+    switch (cmd)
+    {
+    case CODEC_CMD_SET_VOLUME:
+        value = *(int *)args;
+        if (value < 0 || value > 99)
+        {
+            LOG_W("Please volume level 0 ~ 99");
+            result = -RT_EINVAL;
+        }
+        else
+        {
+            LOG_I("Set volume level to %d", value);
+            wm8978_set_volume(snd->i2c_device, value);
+            result = RT_EOK;
+        }
+        break;
+
+    case CODEC_CMD_SAMPLERATE:
+        value = *(int *)args;
+        LOG_I("Set Samplerate %d", value);
+        SAIA_SampleRate_Set(value);
+        break;
+
+    default:
+        result = RT_EOK;
+    }
+    return result;
+}
+
+static rt_size_t sound_write(rt_device_t dev, rt_off_t pos,
+                             const void *buffer, rt_size_t size)
+{
+    int result = RT_EOK;
+    struct sound_device *snd = (struct sound_device *)dev;
+
+    result = rt_data_node_write(snd->node_list, (void *)buffer, size);
+
+    return result;
+}
+
+static rt_err_t sound_close(rt_device_t dev)
+{
+    HAL_SAI_DMAStop(&SAI1A_Handler);
+    LOG_I("Close Sound Device!");
+
+    return RT_EOK;
+}
+
+int rt_hw_sound_hw_init(char *i2c_bus_name)
+{
+    int result = RT_EOK;
+
+    if (sound != RT_NULL)
+        return RT_EOK;
+
+    HAL_SAI_MspInit(NULL);
+    sound = rt_malloc(sizeof(struct sound_device));
+    if (sound == RT_NULL)
+    {
+        LOG_E("malloc memory for sound device failed!");
+        result = -RT_ENOMEM;
+        goto __exit;
+    }
+    memset(sound, 0, sizeof(struct sound_device));
+
+    sound->i2c_device = rt_i2c_bus_device_find(i2c_bus_name);
+    if (sound->i2c_device == RT_NULL)
+    {
+        LOG_E("i2c bus device %s not found!", i2c_bus_name);
+        result = -RT_ENOSYS;
+        goto __exit;
+    }
+
+    sound->send_fifo = rt_malloc(AUDIO_SEND_BUFFER_SIZE);
+    if (sound->send_fifo == RT_NULL)
+    {
+        result = -RT_ENOMEM;
+        goto __exit;
+    }
+    memset(sound->send_fifo, 0, AUDIO_SEND_BUFFER_SIZE);
+
+    rt_data_node_init(&sound->node_list, 10);
+    sound->node_list->read_complete = data_node_read_complete;
+    sound->node_list->user_data = sound;
+
+    sound->parent.type      = RT_Device_Class_Sound;
+    sound->parent.init      = sound_init;
+    sound->parent.open      = sound_open;
+    sound->parent.control   = sound_control;
+    sound->parent.write     = sound_write;
+    sound->parent.read      = RT_NULL;
+    sound->parent.close     = sound_close;
+    sound->parent.user_data = sound;
+
+    /* register the device */
+    rt_device_register(&sound->parent, "sound", RT_DEVICE_FLAG_WRONLY | RT_DEVICE_FLAG_DMA_TX);
+    rt_device_init(&sound->parent);
+
+    return RT_EOK;
+
+__exit:
+    if (sound->send_fifo != RT_NULL)
+    {
+        rt_free(sound->send_fifo);
+        sound->send_fifo = RT_NULL;
+    }
+
+    if (sound != RT_NULL)
+    {
+        rt_free(sound);
+        sound = RT_NULL;
+    }
+
+    return result;
+}
+
+extern int rt_hw_micphone_init(char *i2c_bus_name);
+
+int rt_hw_audio_init(char *i2c_bus_name)
+{
+    rt_hw_sound_hw_init(i2c_bus_name);
+    rt_hw_micphone_init(i2c_bus_name);
+
+    return RT_EOK;
+}

+ 733 - 0
bsp/stm32f429-apollo/drivers/audio/drv_wm8978.c

@@ -0,0 +1,733 @@
+/*
+ * Copyright (c) 2006-2018, RT-Thread Development Team
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2018-11-14     ZeroFree     first implementation
+ */
+
+#include <rtthread.h>
+#include <rtdevice.h>
+
+#include "drv_wm8978.h"
+
+
+/* Register Definitions */
+#define REG_SOFTWARE_RESET      ((uint16_t)0)
+#define REG_POWER_MANAGEMENT1   ((uint16_t)(1 << 9))
+#define REG_POWER_MANAGEMENT2   ((uint16_t)(2 << 9))
+#define REG_POWER_MANAGEMENT3   ((uint16_t)(3 << 9))
+#define REG_AUDIO_INTERFACE     ((uint16_t)(4 << 9))
+#define REG_COMPANDING          ((uint16_t)(5 << 9))
+#define REG_CLOCK_GEN           ((uint16_t)(6 << 9))
+#define REG_ADDITIONAL          ((uint16_t)(7 << 9))
+#define REG_GPIO                ((uint16_t)(8 << 9))
+#define REG_JACK_DETECT1        ((uint16_t)(9 << 9))
+#define REG_DAC                 ((uint16_t)(10 << 9))
+#define REG_LEFT_DAC_VOL        ((uint16_t)(11 << 9))
+#define REG_RIGHT_DAC_VOL       ((uint16_t)(12 << 9))
+#define REG_JACK_DETECT2        ((uint16_t)(13 << 9))
+#define REG_ADC                 ((uint16_t)(14 << 9))
+#define REG_LEFT_ADC_VOL        ((uint16_t)(15 << 9))
+#define REG_RIGHT_ADC_VOL       ((uint16_t)(16 << 9))
+#define REG_EQ1                 ((uint16_t)(18 << 9))
+#define REG_EQ2                 ((uint16_t)(19 << 9))
+#define REG_EQ3                 ((uint16_t)(20 << 9))
+#define REG_EQ4                 ((uint16_t)(21 << 9))
+#define REG_EQ5                 ((uint16_t)(22 << 9))
+#define REG_DAC_LIMITER1        ((uint16_t)(24 << 9))
+#define REG_DAC_LIMITER2        ((uint16_t)(25 << 9))
+#define REG_NOTCH_FILTER1       ((uint16_t)(27 << 9))
+#define REG_NOTCH_FILTER2       ((uint16_t)(28 << 9))
+#define REG_NOTCH_FILTER3       ((uint16_t)(29 << 9))
+#define REG_NOTCH_FILTER4       ((uint16_t)(30 << 9))
+#define REG_ALC1                ((uint16_t)(32 << 9))
+#define REG_ALC2                ((uint16_t)(33 << 9))
+#define REG_ALC3                ((uint16_t)(34 << 9))
+#define REG_NOISE_GATE          ((uint16_t)(35 << 9))
+#define REG_PLL_N               ((uint16_t)(36 << 9))
+#define REG_PLL_K1              ((uint16_t)(37 << 9))
+#define REG_PLL_K2              ((uint16_t)(38 << 9))
+#define REG_PLL_K3              ((uint16_t)(39 << 9))
+#define REG_3D                  ((uint16_t)(41 << 9))
+#define REG_BEEP                ((uint16_t)(43 << 9))
+#define REG_INPUT               ((uint16_t)(44 << 9))
+#define REG_LEFT_PGA_GAIN       ((uint16_t)(45 << 9))
+#define REG_RIGHT_PGA_GAIN      ((uint16_t)(46 << 9))
+#define REG_LEFT_ADC_BOOST      ((uint16_t)(47 << 9))
+#define REG_RIGHT_ADC_BOOST     ((uint16_t)(48 << 9))
+#define REG_OUTPUT              ((uint16_t)(49 << 9))
+#define REG_LEFT_MIXER          ((uint16_t)(50 << 9))
+#define REG_RIGHT_MIXER         ((uint16_t)(51 << 9))
+#define REG_LOUT1_VOL           ((uint16_t)(52 << 9))
+#define REG_ROUT1_VOL           ((uint16_t)(53 << 9))
+#define REG_LOUT2_VOL           ((uint16_t)(54 << 9))
+#define REG_ROUT2_VOL           ((uint16_t)(55 << 9))
+#define REG_OUT3_MIXER          ((uint16_t)(56 << 9))
+#define REG_OUT4_MIXER          ((uint16_t)(57 << 9))
+
+// R01 REG_POWER_MANAGEMENT1
+#define BUFDCOPEN               (1 << 8)
+#define OUT4MIXEN               (1 << 7)
+#define OUT3MIXEN               (1 << 6)
+#define PLLEN                   (1 << 5)
+#define MICBEN                  (1 << 4)
+#define BIASEN                  (1 << 3)
+#define BUFIOEN                 (1 << 2)
+#define VMIDSEL_OFF             (0)
+#define VMIDSEL_75K             (1)
+#define VMIDSEL_300K            (2)
+#define VMIDSEL_5K              (3)
+
+// R02 REG_POWER_MANAGEMENT2
+#define ROUT1EN                 (1 << 8)
+#define LOUT1EN                 (1 << 7)
+#define SLEEP                   (1 << 6)
+#define BOOSTENR                (1 << 5)
+#define BOOSTENL                (1 << 4)
+#define INPPGAENR               (1 << 3)
+#define INPPGAENL               (1 << 2)
+#define ADCENR                  (1 << 1)
+#define ADCENL                  (1)
+
+// R03 REG_POWER_MANAGEMENT3
+#define OUT4EN                  (1 << 8)
+#define OUT3EN                  (1 << 7)
+#define LOUT2EN                 (1 << 6)
+#define ROUT2EN                 (1 << 5)
+#define RMIXEN                  (1 << 3)
+#define LMIXEN                  (1 << 2)
+#define DACENR                  (1 << 1)
+#define DACENL                  (1)
+
+// R04 REG_AUDIO_INTERFACE
+#define BCP_NORMAL              (0)
+#define BCP_INVERTED            (1 << 8)
+#define LRP_NORMAL              (0)
+#define LRP_INVERTED            (1 << 7)
+#define WL_16BITS               (0)
+#define WL_20BITS               (1 << 5)
+#define WL_24BITS               (2 << 5)    // Default value
+#define WL_32BITS               (3 << 5)
+#define FMT_RIGHT_JUSTIFIED     (0)
+#define FMT_LEFT_JUSTIFIED      (1 << 3)
+#define FMT_I2S                 (2 << 3)    // Default value
+#define FMT_PCM                 (3 << 3)
+#define DACLRSWAP               (1 << 2)
+#define ADCLRSWAP               (1 << 1)
+#define MONO                    (1)
+
+// R05 REG_COMPANDING
+#define WL8                     (1 << 5)
+#define DAC_COMP_OFF            (0)         // Default value
+#define DAC_COMP_ULAW           (2 << 3)
+#define DAC_COMP_ALAW           (3 << 3)
+#define ADC_COMP_OFF            (0)         // Default value
+#define ADC_COMP_ULAW           (2 << 1)
+#define ADC_COMP_ALAW           (3 << 1)
+#define LOOPBACK                (1)
+
+// R06 REG_CLOCK_GEN
+#define CLKSEL_MCLK             (0)
+#define CLKSEL_PLL              (1 << 8)    // Default value
+#define MCLK_DIV1               (0)
+#define MCLK_DIV1_5             (1 << 5)
+#define MCLK_DIV2               (2 << 5)    // Default value
+#define MCLK_DIV3               (3 << 5)
+#define MCLK_DIV4               (4 << 5)
+#define MCLK_DIV6               (5 << 5)
+#define MCLK_DIV8               (6 << 5)
+#define MCLK_DIV12              (7 << 5)
+#define BCLK_DIV1               (0)         // Default value
+#define BCLK_DIV2               (1 << 2)
+#define BCLK_DIV4               (2 << 2)
+#define BCLK_DIV8               (3 << 2)
+#define BCLK_DIV16              (4 << 2)
+#define BCLK_DIV32              (5 << 2)
+#define MS                      (1)
+
+// R07 REG_ADDITIONAL
+#define WM_SR_48KHZ             (0)         // Default value
+#define WM_SR_32KHZ             (1 << 1)
+#define WM_SR_24KHZ             (2 << 1)
+#define WM_SR_16KHZ             (3 << 1)
+#define WM_SR_12KHZ             (4 << 1)
+#define WM_SR_8KHZ                  (5 << 1)
+#define SLOWCLKEN               (1)
+
+// R08 REG_GPIO
+#define OPCLK_DIV1              (0)         // Default value
+#define OPCLK_DIV2              (1 << 4)
+#define OPCLK_DIV3              (2 << 4)
+#define OPCLK_DIV4              (3 << 4)
+#define GPIO1POL_NONINVERTED    (0)         // Default value
+#define GPIO1POL_INVERTED       (1 << 3)
+#define GPIO1SEL_INPUT          (0)         // Default value
+#define GPIO1SEL_TEMP_OK        (2)
+#define GPIO1SEL_AMUTE_ACTIVE   (3)
+#define GPIO1SEL_PLL_CLK_OP     (4)
+#define GPIO1SEL_PLL_LOCK       (5)
+#define GPIO1SEL_LOGIC1         (6)
+#define GPIO1SEL_LOGIC0         (7)
+
+// R09 REG_JACK_DETECT1
+#define JD_VMID_EN1             (1 << 8)
+#define JD_VMID_EN0             (1 << 7)
+#define JD_EN                   (1 << 6)
+#define JD_SEL_GPIO1            (0 << 4)    // Default value
+#define JD_SEL_GPIO2            (1 << 4)
+#define JD_SEL_GPIO3            (2 << 4)
+
+// R10 REG_DAC
+#define SOFTMUTE                (1 << 6)
+#define DACOSR128               (1 << 3)
+#define AMUTE                   (1 << 2)
+#define DACPOLR                 (1 << 1)
+#define DACPOLL                 (1)
+
+// R11 & R12 REG_LEFT_DAC_VOL & REG_RIGHT_DAC_VOL
+#define DACVU                   (1 << 8)
+#define DACVOL_POS              (0)
+#define DACVOL_MASK             (0xFF)
+
+// R13 REG_JACK_DETECT2
+#define JD_OUT4_EN1             (1 << 7)
+#define JD_OUT3_EN1             (1 << 6)
+#define JD_OUT2_EN1             (1 << 5)
+#define JD_OUT1_EN1             (1 << 4)
+#define JD_OUT4_EN0             (1 << 3)
+#define JD_OUT3_EN0             (1 << 2)
+#define JD_OUT2_EN0             (1 << 1)
+#define JD_OUT1_EN0             (1)
+
+// R14 REG_ADC
+#define HPFEN                   (1 << 8)
+#define HPFAPP                  (1 << 7)
+#define HPFCUT_POS              (4)
+#define HPFCUT_MASK             (7)
+#define HPFCUT_0                (0)
+#define HPFCUT_1                (1 << 4)
+#define HPFCUT_2                (2 << 4)
+#define HPFCUT_3                (3 << 4)
+#define HPFCUT_4                (4 << 4)
+#define HPFCUT_5                (5 << 4)
+#define HPFCUT_6                (6 << 4)
+#define HPFCUT_7                (7 << 4)
+#define ADCOSR128               (1 << 3)
+#define ADCRPOL                 (1 << 1)
+#define ADCLPOL                 (1)
+
+// R15 & R16 REG_LEFT_ADC_VOL & REG_RIGHT_ADC_VOL
+#define ADCVU                   (1 << 8)
+#define ADCVOL_POS              (0)
+#define ADCVOL_MASK             (0xFF)
+
+// R18 REG_EQ1
+#define EQ3DMODE_ADC            (0)
+#define EQ3DMODE_DAC            (1 << 8)    // Default value
+#define EQ1C_80HZ               (0)
+#define EQ1C_105HZ              (1 << 5)    // Default value
+#define EQ1C_135HZ              (2 << 5)
+#define EQ1C_175HZ              (3 << 5)
+
+// R19 REG_EQ2
+#define EQ2BW_NARROW            (0)         // Default value
+#define EQ2BW_WIDE              (1 << 8)
+#define EQ2C_230HZ              (0)
+#define EQ2C_300HZ              (1 << 5)    // Default value
+#define EQ2C_385HZ              (2 << 5)
+#define EQ2C_500HZ              (3 << 5)
+
+// R20 REG_EQ3
+#define EQ3BW_NARROW            (0)         // Default value
+#define EQ3BW_WIDE              (1 << 8)
+#define EQ3C_650HZ              (0)
+#define EQ3C_850HZ              (1 << 5)    // Default value
+#define EQ3C_1_1KHZ             (2 << 5)
+#define EQ3C_1_4KHZ             (3 << 5)
+
+// R21 REG_EQ4
+#define EQ4BW_NARROW            (0)         // Default value
+#define EQ4BW_WIDE              (1 << 8)
+#define EQ4C_1_8KHZ             (0)
+#define EQ4C_2_4KHZ             (1 << 5)    // Default value
+#define EQ4C_3_2KHZ             (2 << 5)
+#define EQ4C_4_1KHZ             (3 << 5)
+
+// R22 REG_EQ5
+#define EQ5C_5_3KHZ             (0)
+#define EQ5C_6_9KHZ             (1 << 5)    // Default value
+#define EQ5C_9KHZ               (2 << 5)
+#define EQ5C_11_7KHZ            (3 << 5)
+
+// R18 - R22
+#define EQC_POS                 (5)
+#define EQC_MASK                (3)
+#define EQG_POS                 (0)
+#define EQG_MASK                (31)
+
+// R24 REG_DAC_LIMITER1
+#define LIMEN                   (1 << 8)
+#define LIMDCY_POS              (4)
+#define LIMDCY_MASK             (15)
+#define LIMDCY_750US            (0)
+#define LIMDCY_1_5MS            (1 << 4)
+#define LIMDCY_3MS              (2 << 4)
+#define LIMDCY_6MS              (3 << 4)    // Default value
+#define LIMDCY_12MS             (4 << 4)
+#define LIMDCY_24MS             (5 << 4)
+#define LIMDCY_48MS             (6 << 4)
+#define LIMDCY_96MS             (7 << 4)
+#define LIMDCY_192MS            (8 << 4)
+#define LIMDCY_384MS            (9 << 4)
+#define LIMDCY_768MS            (10 << 4)
+#define LIMATK_POS              (0)
+#define LIMATK_MASK             (15)
+#define LIMATK_94US             (0)
+#define LIMATK_188US            (1)
+#define LIMATK_375US            (2)         // Default value
+#define LIMATK_750US            (3)
+#define LIMATK_1_5MS            (4)
+#define LIMATK_3MS              (5)
+#define LIMATK_6MS              (6)
+#define LIMATK_12MS             (7)
+#define LIMATK_24MS             (8)
+#define LIMATK_48MS             (9)
+#define LIMATK_96MS             (10)
+#define LIMATK_192MS            (11)
+
+// R25 REG_DAC_LIMITER2
+#define LIMLVL_POS              (4)
+#define LIMLVL_MASK             (7)
+#define LIMLVL_N1DB             (0)         // Default value
+#define LIMLVL_N2DB             (1 << 4)
+#define LIMLVL_N3DB             (2 << 4)
+#define LIMLVL_N4DB             (3 << 4)
+#define LIMLVL_N5DB             (4 << 4)
+#define LIMLVL_N6DB             (5 << 4)
+#define LIMBOOST_POS            (0)
+#define LIMBOOST_MASK           (15)
+#define LIMBOOST_0DB            (0)
+#define LIMBOOST_1DB            (1)
+#define LIMBOOST_2DB            (2)
+#define LIMBOOST_3DB            (3)
+#define LIMBOOST_4DB            (4)
+#define LIMBOOST_5DB            (5)
+#define LIMBOOST_6DB            (6)
+#define LIMBOOST_7DB            (7)
+#define LIMBOOST_8DB            (8)
+#define LIMBOOST_9DB            (9)
+#define LIMBOOST_10DB           (10)
+#define LIMBOOST_11DB           (11)
+#define LIMBOOST_12DB           (12)
+
+// R27 - R30 REG_NOTCH_FILTER1 - REG_NOTCH_FILTER4
+#define NFU                     (1 << 8)
+#define NFEN                    (1 << 7)
+#define NFA_POS                 (0)
+#define NFA_MASK                (127)
+
+// R32 REG_ALC1
+#define ALCSEL_OFF              (0)         // Default value
+#define ALCSEL_RIGHT_ONLY       (1 << 7)
+#define ALCSEL_LEFT_ONLY        (2 << 7)
+#define ALCSEL_BOTH_ON          (3 << 7)
+#define ALCMAXGAIN_POS          (3)
+#define ALCMAXGAIN_MASK         (7)
+#define ALCMAXGAIN_N6_75DB      (0)
+#define ALCMAXGAIN_N0_75DB      (1 << 3)
+#define ALCMAXGAIN_5_25DB       (2 << 3)
+#define ALCMAXGAIN_11_25DB      (3 << 3)
+#define ALCMAXGAIN_17_25DB      (4 << 3)
+#define ALCMAXGAIN_23_25DB      (5 << 3)
+#define ALCMAXGAIN_29_25DB      (6 << 3)
+#define ALCMAXGAIN_35_25DB      (7 << 3)    // Default value
+#define ALCMINGAIN_POS          (0)
+#define ALCMINGAIN_MASK         (7)
+#define ALCMINGAIN_N12DB        (0)         // Default value
+#define ALCMINGAIN_N6DB         (1)
+#define ALCMINGAIN_0DB          (2)
+#define ALCMINGAIN_6DB          (3)
+#define ALCMINGAIN_12DB         (4)
+#define ALCMINGAIN_18DB         (5)
+#define ALCMINGAIN_24DB         (6)
+#define ALCMINGAIN_30DB         (7)
+
+// R33 REG_ALC2
+#define ALCHLD_POS              (4)
+#define ALCHLD_MASK             (15)
+#define ALCHLD_0MS              (0)         // Default value
+#define ALCHLD_2_67MS           (1 << 4)
+#define ALCHLD_5_33MS           (2 << 4)
+#define ALCHLD_10_67MS          (3 << 4)
+#define ALCHLD_21_33MS          (4 << 4)
+#define ALCHLD_42_67MS          (5 << 4)
+#define ALCHLD_85_33MS          (6 << 4)
+#define ALCHLD_170_67MS         (7 << 4)
+#define ALCHLD_341_33MS         (8 << 4)
+#define ALCHLD_682_67MS         (9 << 4)
+#define ALCHLD_1_36S            (10 << 4)
+#define ALCLVL_POS              (0)
+#define ALCLVL_MASK             (15)
+#define ALCLVL_N22_5DBFS        (0)
+#define ALCLVL_N21DBFS          (1)
+#define ALCLVL_N19_5DBFS        (2)
+#define ALCLVL_N18DBFS          (3)
+#define ALCLVL_N16_5DBFS        (4)
+#define ALCLVL_N15DBFS          (5)
+#define ALCLVL_N13_5DBFS        (6)
+#define ALCLVL_N12DBFS          (7)
+#define ALCLVL_N10_5DBFS        (8)
+#define ALCLVL_N9DBFS           (9)
+#define ALCLVL_N7_5DBFS         (10)
+#define ALCLVL_N6DBFS           (11)        // Default value
+#define ALCLVL_N4_5DBFS         (12)
+#define ALCLVL_N3DBFS           (13)
+#define ALCLVL_N1_5DBFS         (14)
+
+// R34 REG_ALC3
+#define ALCMODE_ALC             (0)         // Default value
+#define ALCMODE_LIMITER         (1 << 8)
+#define ALCDCY_POS              (4)
+#define ALCDCY_MASK             (15)
+#define ALCDCY_0                (0)
+#define ALCDCY_1                (1 << 4)
+#define ALCDCY_2                (2 << 4)
+#define ALCDCY_3                (3 << 4)    // Default value
+#define ALCDCY_4                (4 << 4)
+#define ALCDCY_5                (5 << 4)
+#define ALCDCY_6                (6 << 4)
+#define ALCDCY_7                (7 << 4)
+#define ALCDCY_8                (8 << 4)
+#define ALCDCY_9                (9 << 4)
+#define ALCDCY_10               (10 << 4)
+#define ALCATK_POS              (0)
+#define ALCATK_MASK             (15)
+#define ALCATK_0                (0)
+#define ALCATK_1                (1)
+#define ALCATK_2                (2)         // Default value
+#define ALCATK_3                (3)
+#define ALCATK_4                (4)
+#define ALCATK_5                (5)
+#define ALCATK_6                (6)
+#define ALCATK_7                (7)
+#define ALCATK_8                (8)
+#define ALCATK_9                (9)
+#define ALCATK_10               (10)
+
+// R35 REG_NOISE_GATE
+#define NGEN                    (1 << 3)
+#define NGTH_POS                (0)
+#define NGTH_MASK               (7)
+#define NGTH_N39DB              (0)         // Default value
+#define NGTH_N45DB              (1)
+#define NGTH_N51DB              (2)
+#define NGTH_N57DB              (3)
+#define NGTH_N63DB              (4)
+#define NGTH_N69DB              (5)
+#define NGTH_N75DB              (6)
+#define NGTH_N81DB              (7)
+
+// R36 REG_PLL_N
+#define PLLPRESCALE             (1 << 4)
+#define PLLN_POS                (0)
+#define PLLN_MASK               (15)
+
+// R37 - R39 REG_PLL_K1 - REG_PLL_K3
+#define PLLK1_POS               (0)
+#define PLLK1_MASK              (63)
+#define PLLK2_POS               (0)
+#define PLLK2_MASK              (511)
+#define PLLK3_POS               (0)
+#define PLLK3_MASK              (511)
+
+// R41 REG_3D
+#define DEPTH3D_POS             (0)
+#define DEPTH3D_MASK            (15)
+#define DEPTH3D_0               (0)         // Default value
+#define DEPTH3D_6_67            (1)
+#define DEPTH3D_13_33           (2)
+#define DEPTH3D_20              (3)
+#define DEPTH3D_26_67           (4)
+#define DEPTH3D_33_33           (5)
+#define DEPTH3D_40              (6)
+#define DEPTH3D_46_67           (7)
+#define DEPTH3D_53_33           (8)
+#define DEPTH3D_60              (9)
+#define DEPTH3D_66_67           (10)
+#define DEPTH3D_73_33           (11)
+#define DEPTH3D_80              (12)
+#define DEPTH3D_86_67           (13)
+#define DEPTH3D_93_33           (14)
+#define DEPTH3D_100             (15)
+
+// R43 REG_BEEP
+#define MUTERPGA2INV            (1 << 5)
+#define INVROUT2                (1 << 4)
+#define BEEPVOL_POS             (1)
+#define BEEPVOL_MASK            (7)
+#define BEEPVOL_N15DB           (0)
+#define BEEPVOL_N12DB           (1 << 1)
+#define BEEPVOL_N9DB            (2 << 1)
+#define BEEPVOL_N6DB            (3 << 1)
+#define BEEPVOL_N3DB            (4 << 1)
+#define BEEPVOL_0DB             (5 << 1)
+#define BEEPVOL_3DB             (6 << 1)
+#define BEEPVOL_6DB             (7 << 1)
+#define BEEPEN                  (1)
+
+// R44 REG_INPUT
+#define MBVSEL_0_9AVDD          (0)         // Default value
+#define MBVSEL_0_65AVDD         (1 << 8)
+#define R2_2INPVGA              (1 << 6)
+#define RIN2INPVGA              (1 << 5)    // Default value
+#define RIP2INPVGA              (1 << 4)    // Default value
+#define L2_2INPVGA              (1 << 2)
+#define LIN2INPVGA              (1 << 1)    // Default value
+#define LIP2INPVGA              (1)         // Default value
+
+// R45 REG_LEFT_PGA_GAIN
+#define INPPGAUPDATE            (1 << 8)
+#define INPPGAZCL               (1 << 7)
+#define INPPGAMUTEL             (1 << 6)
+
+// R46 REG_RIGHT_PGA_GAIN
+#define INPPGAZCR               (1 << 7)
+#define INPPGAMUTER             (1 << 6)
+
+// R45 - R46
+#define INPPGAVOL_POS           (0)
+#define INPPGAVOL_MASK          (63)
+
+// R47 REG_LEFT_ADC_BOOST
+#define PGABOOSTL               (1 << 8)    // Default value
+#define L2_2BOOSTVOL_POS        (4)
+#define L2_2BOOSTVOL_MASK       (7)
+#define L2_2BOOSTVOL_DISABLED   (0)         // Default value
+#define L2_2BOOSTVOL_N12DB      (1 << 4)
+#define L2_2BOOSTVOL_N9DB       (2 << 4)
+#define L2_2BOOSTVOL_N6DB       (3 << 4)
+#define L2_2BOOSTVOL_N3DB       (4 << 4)
+#define L2_2BOOSTVOL_0DB        (5 << 4)
+#define L2_2BOOSTVOL_3DB        (6 << 4)
+#define L2_2BOOSTVOL_6DB        (7 << 4)
+#define AUXL2BOOSTVOL_POS       (0)
+#define AUXL2BOOSTVOL_MASK      (7)
+#define AUXL2BOOSTVOL_DISABLED  (0)         // Default value
+#define AUXL2BOOSTVOL_N12DB     (1)
+#define AUXL2BOOSTVOL_N9DB      (2)
+#define AUXL2BOOSTVOL_N6DB      (3)
+#define AUXL2BOOSTVOL_N3DB      (4)
+#define AUXL2BOOSTVOL_0DB       (5)
+#define AUXL2BOOSTVOL_3DB       (6)
+#define AUXL2BOOSTVOL_6DB       (7)
+
+// R48 REG_RIGHT_ADC_BOOST
+#define PGABOOSTR               (1 << 8)    // Default value
+#define R2_2BOOSTVOL_POS        (4)
+#define R2_2BOOSTVOL_MASK       (7)
+#define R2_2BOOSTVOL_DISABLED   (0)         // Default value
+#define R2_2BOOSTVOL_N12DB      (1 << 4)
+#define R2_2BOOSTVOL_N9DB       (2 << 4)
+#define R2_2BOOSTVOL_N6DB       (3 << 4)
+#define R2_2BOOSTVOL_N3DB       (4 << 4)
+#define R2_2BOOSTVOL_0DB        (5 << 4)
+#define R2_2BOOSTVOL_3DB        (6 << 4)
+#define R2_2BOOSTVOL_6DB        (7 << 4)
+#define AUXR2BOOSTVOL_POS       (0)
+#define AUXR2BOOSTVOL_MASK      (7)
+#define AUXR2BOOSTVOL_DISABLED  (0)         // Default value
+#define AUXR2BOOSTVOL_N12DB     (1)
+#define AUXR2BOOSTVOL_N9DB      (2)
+#define AUXR2BOOSTVOL_N6DB      (3)
+#define AUXR2BOOSTVOL_N3DB      (4)
+#define AUXR2BOOSTVOL_0DB       (5)
+#define AUXR2BOOSTVOL_3DB       (6)
+#define AUXR2BOOSTVOL_6DB       (7)
+
+// R49 REG_OUTPUT
+#define DACL2RMIX               (1 << 6)
+#define DACR2LMIX               (1 << 5)
+#define OUT4BOOST               (1 << 4)
+#define OUT3BOOST               (1 << 3)
+#define SPKBOOST                (1 << 2)
+#define TSDEN                   (1 << 1)
+#define VROI                    (1)
+
+// R50 REG_LEFT_MIXER
+#define AUXLMIXVOL_POS          (6)
+#define AUXLMIXVOL_MASK         (7)
+#define AUXLMIXVOL_N15DB        (0)         // Default value
+#define AUXLMIXVOL_N12DB        (1 << 6)
+#define AUXLMIXVOL_N9DB         (2 << 6)
+#define AUXLMIXVOL_N6DB         (3 << 6)
+#define AUXLMIXVOL_N3DB         (4 << 6)
+#define AUXLMIXVOL_0DB          (5 << 6)
+#define AUXLMIXVOL_3DB          (6 << 6)
+#define AUXLMIXVOL_6DB          (7 << 6)
+#define AUXL2LMIX               (1 << 5)
+#define BYPLMIXVOL_POS          (2)
+#define BYPLMIXVOL_MASK         (7)
+#define BYPLMIXVOL_N15DB        (0)         // Default value
+#define BYPLMIXVOL_N12DB        (1 << 2)
+#define BYPLMIXVOL_N9DB         (2 << 2)
+#define BYPLMIXVOL_N6DB         (3 << 2)
+#define BYPLMIXVOL_N3DB         (4 << 2)
+#define BYPLMIXVOL_0DB          (5 << 2)
+#define BYPLMIXVOL_3DB          (6 << 2)
+#define BYPLMIXVOL_6DB          (7 << 2)
+#define BYPL2LMIX               (1 << 1)
+#define DACL2LMIX               (1)
+
+// R51 REG_RIGHT_MIXER
+#define AUXRMIXVOL_POS          (6)
+#define AUXRMIXVOL_MASK         (7)
+#define AUXRMIXVOL_N15DB        (0)         // Default value
+#define AUXRMIXVOL_N12DB        (1 << 6)
+#define AUXRMIXVOL_N9DB         (2 << 6)
+#define AUXRMIXVOL_N6DB         (3 << 6)
+#define AUXRMIXVOL_N3DB         (4 << 6)
+#define AUXRMIXVOL_0DB          (5 << 6)
+#define AUXRMIXVOL_3DB          (6 << 6)
+#define AUXRMIXVOL_6DB          (7 << 6)
+#define AUXR2RMIX               (1 << 5)
+#define BYPRMIXVOL_POS          (2)
+#define BYPRMIXVOL_MASK         (7)
+#define BYPRMIXVOL_N15DB        (0)         // Default value
+#define BYPRMIXVOL_N12DB        (1 << 2)
+#define BYPRMIXVOL_N9DB         (2 << 2)
+#define BYPRMIXVOL_N6DB         (3 << 2)
+#define BYPRMIXVOL_N3DB         (4 << 2)
+#define BYPRMIXVOL_0DB          (5 << 2)
+#define BYPRMIXVOL_3DB          (6 << 2)
+#define BYPRMIXVOL_6DB          (7 << 2)
+#define BYPR2RMIX               (1 << 1)
+#define DACR2RMIX               (1)
+
+// R52 - R55 REG_LOUT1_VOL - REG_ROUT2_VOL
+#define HPVU                    (1 << 8)
+#define SPKVU                   (1 << 8)
+#define LOUT1ZC                 (1 << 7)
+#define LOUT1MUTE               (1 << 6)
+#define ROUT1ZC                 (1 << 7)
+#define ROUT1MUTE               (1 << 6)
+#define LOUT2ZC                 (1 << 7)
+#define LOUT2MUTE               (1 << 6)
+#define ROUT2ZC                 (1 << 7)
+#define ROUT2MUTE               (1 << 6)
+#define VOL_POS                 (0)
+#define VOL_MASK                (63)
+
+// R56 REG_OUT3_MIXER
+#define OUT3MUTE                (1 << 6)
+#define OUT4_2OUT3              (1 << 3)
+#define BYPL2OUT3               (1 << 2)
+#define LMIX2OUT3               (1 << 1)
+#define LDAC2OUT3               (1)
+
+// R57 REG_OUT4_MIXER
+#define OUT4MUTE                (1 << 6)
+#define HALFSIG                 (1 << 5)
+#define LMIX2OUT4               (1 << 4)
+#define LDAC2OUT4               (1 << 3)
+#define BYPR2OUT4               (1 << 2)
+#define RMIX2OUT4               (1 << 1)
+#define RDAC2OUT4               (1)
+
+static void write_reg(struct rt_i2c_bus_device *dev, rt_uint16_t s_data)
+{
+    struct rt_i2c_msg msg;
+    rt_uint8_t send_buffer[2];
+    RT_ASSERT(dev != RT_NULL);
+    send_buffer[0] = (rt_uint8_t)(s_data >> 8);
+    send_buffer[1] = (rt_uint8_t)(s_data);
+    msg.addr = 0x1A;
+    msg.flags = RT_I2C_WR;
+    msg.len = 2;
+    msg.buf = send_buffer;
+    rt_i2c_transfer(dev, &msg, 1);
+}
+
+/**
+  * @brief  Init WM8978 Codec device.
+  * @param  dev: I2C device handle
+  * @retval RT_EOK if correct communication, else wrong communication
+  */
+int wm8978_init(struct rt_i2c_bus_device *dev)
+{
+    write_reg(dev, REG_SOFTWARE_RESET);
+
+    /* 1.5x boost power up sequence,Mute all outputs. */
+    write_reg(dev, REG_LOUT1_VOL | LOUT1MUTE);
+    write_reg(dev, REG_ROUT1_VOL | ROUT1MUTE);
+    write_reg(dev, REG_LOUT2_VOL | LOUT2MUTE);
+    write_reg(dev, REG_ROUT2_VOL | ROUT2MUTE);
+
+    /* Enable unused output chosen from L/ROUT2, OUT3 or OUT4. */
+    write_reg(dev, REG_POWER_MANAGEMENT3 | OUT4EN);
+    /* Set BUFDCOPEN=1 and BUFIOEN=1 in register R1 */
+    write_reg(dev, REG_POWER_MANAGEMENT1 | BUFDCOPEN | BUFIOEN);
+    /* Set SPKBOOST=1 in register R49. */
+    write_reg(dev, REG_OUTPUT | SPKBOOST);
+    /* Set VMIDSEL[1:0] to required value in register R1. */
+    write_reg(dev, REG_POWER_MANAGEMENT1 | BUFDCOPEN | BUFIOEN | VMIDSEL_75K);
+    /* Set L/RMIXEN=1 and DACENL/R=1 in register R3.*/
+    write_reg(dev, REG_POWER_MANAGEMENT3 | LMIXEN | RMIXEN | DACENL | DACENR);
+    /* Set BIASEN=1 in register R1. */
+    write_reg(dev, REG_POWER_MANAGEMENT1 | BUFDCOPEN | BUFIOEN | VMIDSEL_75K);
+    /* Set L/ROUT2EN=1 in register R3. */
+    write_reg(dev, REG_POWER_MANAGEMENT3 | LMIXEN | RMIXEN | DACENL | DACENR | LOUT2EN | ROUT2EN);
+    /* Enable other mixers as required. */
+    /* Enable other outputs as required. */
+    write_reg(dev, REG_POWER_MANAGEMENT2 | LOUT1EN | ROUT1EN | BOOSTENL | BOOSTENR | INPPGAENL | INPPGAENR);
+    write_reg(dev, REG_POWER_MANAGEMENT2 | LOUT1EN | ROUT1EN | BOOSTENL | BOOSTENR | INPPGAENL | INPPGAENR | ADCENL | ADCENR);
+
+    /* Digital inferface setup. */
+    write_reg(dev, REG_AUDIO_INTERFACE | BCP_NORMAL | LRP_NORMAL | WL_16BITS | FMT_I2S);
+
+    write_reg(dev, REG_ADDITIONAL | WM_SR_8KHZ);
+
+    write_reg(dev, REG_POWER_MANAGEMENT1 | BUFDCOPEN | BUFIOEN | VMIDSEL_75K | MICBEN | BIASEN);
+    write_reg(dev, REG_CLOCK_GEN | CLKSEL_MCLK | MCLK_DIV1);
+
+    /* Enable DAC 128x oversampling. */
+    write_reg(dev, REG_DAC | DACOSR128);
+
+    /* Set LOUT2/ROUT2 in BTL operation. */
+    write_reg(dev, REG_BEEP | INVROUT2);
+
+    /* MIC config. */
+    write_reg(dev, REG_INPUT | MBVSEL_0_65AVDD | RIN2INPVGA | RIP2INPVGA | LIN2INPVGA | LIP2INPVGA);
+
+    /* MIC PGA -12db to 35.25db, 0.75setp default: 16(0db). */
+    write_reg(dev, REG_LEFT_PGA_GAIN  | INPPGAZCL | (36 & INPPGAVOL_MASK));
+    write_reg(dev, REG_RIGHT_PGA_GAIN | INPPGAZCR | (36 & INPPGAVOL_MASK) | INPPGAUPDATE);
+
+    write_reg(dev, REG_LEFT_ADC_BOOST | PGABOOSTL | L2_2BOOSTVOL_DISABLED | AUXL2BOOSTVOL_DISABLED);
+    write_reg(dev, REG_RIGHT_ADC_BOOST | PGABOOSTR | R2_2BOOSTVOL_DISABLED | AUXR2BOOSTVOL_DISABLED);
+
+    /* Set output volume. */
+    wm8978_set_volume(dev, 55);
+
+    return RT_EOK;
+}
+
+/**
+  * @brief  Set WM8978 DAC volume level.
+  * @param  dev: I2C device handle
+  * @param  vol: volume level(0 ~ 99)
+  * @retval RT_EOK if correct communication, else wrong communication
+  */
+int wm8978_set_volume(struct rt_i2c_bus_device *dev, int vol)
+{
+    vol = 63 * vol / 100;
+    vol = (vol & VOL_MASK) << VOL_POS;
+    write_reg(dev, REG_LOUT1_VOL | vol);
+    write_reg(dev, REG_ROUT1_VOL | HPVU | vol);
+    write_reg(dev, REG_LOUT2_VOL | vol);
+    write_reg(dev, REG_ROUT2_VOL | SPKVU | vol);
+
+    return RT_EOK;
+}

+ 19 - 0
bsp/stm32f429-apollo/drivers/audio/drv_wm8978.h

@@ -0,0 +1,19 @@
+/*
+ * Copyright (c) 2006-2018, RT-Thread Development Team
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2018-11-14     ZeroFree     first implementation
+ */
+#ifndef __DRV_WM8978_H__
+#define __DRV_WM8978_H__
+
+#include <rtthread.h>
+#include <rtdevice.h>
+
+int wm8978_init(struct rt_i2c_bus_device *dev);
+int wm8978_set_volume(struct rt_i2c_bus_device *dev, int vol);
+
+#endif

+ 2 - 1
bsp/stm32f429-apollo/drivers/drv_spi.c

@@ -539,7 +539,7 @@ struct stm32f4_spi stm32f4_spi5 =
 
 static struct rt_spi_bus spi5_bus;
 
-
+#ifdef SPI_USE_DMA
 /**
   * @brief  This function handles DMA Rx interrupt request.
   * @param  None
@@ -558,6 +558,7 @@ void DMA2_Stream4_IRQHandler(void)
 {
     HAL_DMA_IRQHandler(stm32f4_spi5.spi_handle.hdmatx);
 }
+#endif /* SPI_USE_DMA */
 
 #endif
 

+ 1 - 1
bsp/stm32f429-apollo/drivers/stm32f4xx_hal_conf.h

@@ -71,7 +71,7 @@
 /* #define HAL_LTDC_MODULE_ENABLED   */
 /* #define HAL_RNG_MODULE_ENABLED   */
 #define HAL_RTC_MODULE_ENABLED   /* */
-/* #define HAL_SAI_MODULE_ENABLED   */
+#define HAL_SAI_MODULE_ENABLED   /* */
 #define HAL_SD_MODULE_ENABLED   /* */
 #define HAL_SPI_MODULE_ENABLED
 /* #define HAL_TIM_MODULE_ENABLED   */