Browse Source

more esp32/esp32-s3 convergence

philippe44 1 year ago
parent
commit
8ef3f8178b

+ 10 - 5
components/_override/CMakeLists.txt

@@ -1,6 +1,11 @@
 set(lib_dir ${build_dir}/esp-idf)
 
-set(driver i2s.c i2s_hal.c spi_bus_lock.c)
+if(IDF_TARGET STREQUAL esp32)
+    set(driver esp32/i2s.c esp32/i2s_hal.c esp32/spi_bus_lock.c)
+else()
+    return()
+endif()    
+
 string(REPLACE ".c" ".c.obj" driver_obj "${driver}")
 
 idf_component_register( SRCS ${driver}
@@ -8,14 +13,14 @@ idf_component_register( SRCS ${driver}
 					INCLUDE_DIRS ${IDF_PATH}/components/driver
 					PRIV_INCLUDE_DIRS ${IDF_PATH}/components/driver/include/driver
 )
- 
+
 # CMake is just a pile of crap
-message("!! overriding ${driver} !!")
-message("CAREFUL, LIBRARIES STRIPPING FROM DUPLICATED COMPONENTS DEPENDS ON THIS BEING REBUILD")
+message(STATUS "!! overriding ${driver} !!")
+message(STATUS "CAREFUL, LIBRARIES STRIPPING FROM DUPLICATED COMPONENTS DEPENDS ON THIS BEING REBUILD")
 
 add_custom_command(
 			TARGET ${COMPONENT_LIB}
 			PRE_LINK
 			COMMAND xtensa-esp32-elf-ar -d ${lib_dir}/driver/libdriver.a ${driver_obj}
 			VERBATIM
-)
+)

+ 0 - 0
components/_override/i2s.c → components/_override/esp32/i2s.c


+ 0 - 0
components/_override/i2s_hal.c → components/_override/esp32/i2s_hal.c


+ 0 - 0
components/_override/spi_bus_lock.c → components/_override/esp32/spi_bus_lock.c


+ 1 - 1
components/_override/spi_master.c.unused → components/_override/esp32/spi_master.c

@@ -935,7 +935,7 @@ esp_err_t SPI_MASTER_ISR_ATTR spi_device_polling_start(spi_device_handle_t handl
     ret = check_trans_valid(handle, trans_desc);
     if (ret!=ESP_OK) return ret;
     SPI_CHECK(!spi_bus_device_is_polling(handle), "Cannot send polling transaction while the previous polling transaction is not terminated.", ESP_ERR_INVALID_STATE );
-
+ESP_LOGI("gragra", "LOCAL SPI_MASTER");
     /* If device_acquiring_lock is set to handle, it means that the user has already
      * acquired the bus thanks to the function `spi_device_acquire_bus()`.
      * In that case, we don't need to take the lock again. */

+ 1047 - 0
components/_override/esp32/spi_master.c.debug

@@ -0,0 +1,1047 @@
+// Copyright 2015-2020 Espressif Systems (Shanghai) PTE LTD
+//
+// 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.
+
+/*
+Architecture:
+
+We can initialize a SPI driver, but we don't talk to the SPI driver itself, we address a device. A device essentially
+is a combination of SPI port and CS pin, plus some information about the specifics of communication to the device
+(timing, command/address length etc). The arbitration between tasks is also in conception of devices.
+
+A device can work in interrupt mode and polling mode, and a third but
+complicated mode which combines the two modes above:
+
+1. Work in the ISR with a set of queues; one per device.
+
+   The idea is that to send something to a SPI device, you allocate a
+   transaction descriptor. It contains some information about the transfer
+   like the lenghth, address, command etc, plus pointers to transmit and
+   receive buffer. The address of this block gets pushed into the transmit
+   queue. The SPI driver does its magic, and sends and retrieves the data
+   eventually. The data gets written to the receive buffers, if needed the
+   transaction descriptor is modified to indicate returned parameters and
+   the entire thing goes into the return queue, where whatever software
+   initiated the transaction can retrieve it.
+
+   The entire thing is run from the SPI interrupt handler. If SPI is done
+   transmitting/receiving but nothing is in the queue, it will not clear the
+   SPI interrupt but just disable it by esp_intr_disable. This way, when a
+   new thing is sent, pushing the packet into the send queue and re-enabling
+   the interrupt (by esp_intr_enable) will trigger the interrupt again, which
+   can then take care of the sending.
+
+2. Work in the polling mode in the task.
+
+   In this mode we get rid of the ISR, FreeRTOS queue and task switching, the
+   task is no longer blocked during a transaction. This increase the cpu
+   load, but decrease the interval of SPI transactions. Each time only one
+   device (in one task) can send polling transactions, transactions to
+   other devices are blocked until the polling transaction of current device
+   is done.
+
+   In the polling mode, the queue is not used, all the operations are done
+   in the task. The task calls ``spi_device_polling_start`` to setup and start
+   a new transaction, then call ``spi_device_polling_end`` to handle the
+   return value of the transaction.
+
+   To handle the arbitration among devices, the device "temporarily" acquire
+   a bus by the ``device_acquire_bus_internal`` function, which writes
+   dev_request by CAS operation. Other devices which wants to send polling
+   transactions but don't own the bus will block and wait until given the
+   semaphore which indicates the ownership of bus.
+
+   In case of the ISR is still sending transactions to other devices, the ISR
+   should maintain an ``random_idle`` flag indicating that it's not doing
+   transactions. When the bus is locked, the ISR can only send new
+   transactions to the acquiring device. The ISR will automatically disable
+   itself and send semaphore to the device if the ISR is free. If the device
+   sees the random_idle flag, it can directly start its polling transaction.
+   Otherwise it should block and wait for the semaphore from the ISR.
+
+   After the polling transaction, the driver will release the bus. During the
+   release of the bus, the driver search all other devices to see whether
+   there is any device waiting to acquire the bus, if so, acquire for it and
+   send it a semaphore if the device queue is empty, or invoke the ISR for
+   it. If all other devices don't need to acquire the bus, but there are
+   still transactions in the queues, the ISR will also be invoked.
+
+   To get better polling efficiency, user can call ``spi_device_acquire_bus``
+   function, which also calls the ``spi_bus_lock_acquire_core`` function,
+   before a series of polling transactions to a device. The bus acquiring and
+   task switching before and after the polling transaction will be escaped.
+
+3. Mixed mode
+
+   The driver is written under the assumption that polling and interrupt
+   transactions are not happening simultaneously. When sending polling
+   transactions, it will check whether the ISR is active, which includes the
+   case the ISR is sending the interrupt transactions of the acquiring
+   device. If the ISR is still working, the routine sending a polling
+   transaction will get blocked and wait until the semaphore from the ISR
+   which indicates the ISR is free now.
+
+   A fatal case is, a polling transaction is in flight, but the ISR received
+   an interrupt transaction. The behavior of the driver is unpredictable,
+   which should be strictly forbidden.
+
+We have two bits to control the interrupt:
+
+1. The slave->trans_done bit, which is automatically asserted when a transaction is done.
+
+   This bit is cleared during an interrupt transaction, so that the interrupt
+   will be triggered when the transaction is done, or the SW can check the
+   bit to see if the transaction is done for polling transactions.
+
+   When no transaction is in-flight, the bit is kept active, so that the SW
+   can easily invoke the ISR by enable the interrupt.
+
+2. The system interrupt enable/disable, controlled by esp_intr_enable and esp_intr_disable.
+
+   The interrupt is disabled (by the ISR itself) when no interrupt transaction
+   is queued. When the bus is not occupied, any task, which queues a
+   transaction into the queue, will enable the interrupt to invoke the ISR.
+   When the bus is occupied by a device, other device will put off the
+   invoking of ISR to the moment when the bus is released. The device
+   acquiring the bus can still send interrupt transactions by enable the
+   interrupt.
+
+*/
+
+#include <string.h>
+#include "driver/spi_common_internal.h"
+#include "driver/spi_master.h"
+
+#include "esp_log.h"
+#include "freertos/task.h"
+#include "freertos/queue.h"
+#include "freertos/semphr.h"
+#include "soc/soc_memory_layout.h"
+#include "driver/gpio.h"
+#include "hal/spi_hal.h"
+#include "esp_heap_caps.h"
+
+
+typedef struct spi_device_t spi_device_t;
+
+/// struct to hold private transaction data (like tx and rx buffer for DMA).
+typedef struct {
+    spi_transaction_t   *trans;
+    const uint32_t *buffer_to_send;   //equals to tx_data, if SPI_TRANS_USE_RXDATA is applied; otherwise if original buffer wasn't in DMA-capable memory, this gets the address of a temporary buffer that is;
+                                //otherwise sets to the original buffer or NULL if no buffer is assigned.
+    uint32_t *buffer_to_rcv;    // similar to buffer_to_send
+} spi_trans_priv_t;
+
+typedef struct {
+    int id;
+    spi_device_t* device[DEV_NUM_MAX];
+    intr_handle_t intr;
+    spi_hal_context_t hal;
+    spi_trans_priv_t cur_trans_buf;
+    int cur_cs;     //current device doing transaction
+    const spi_bus_attr_t* bus_attr;
+
+    /**
+     * the bus is permanently controlled by a device until `spi_bus_release_bus`` is called. Otherwise
+     * the acquiring of SPI bus will be freed when `spi_device_polling_end` is called.
+     */
+    spi_device_t* device_acquiring_lock;
+
+//debug information
+    bool polling;   //in process of a polling, avoid of queue new transactions into ISR
+	
+//	PATCH
+	SemaphoreHandle_t mutex;
+	int count;	
+} spi_host_t;
+
+struct spi_device_t {
+    int id;
+    QueueHandle_t trans_queue;
+    QueueHandle_t ret_queue;
+    spi_device_interface_config_t cfg;
+    spi_hal_dev_config_t hal_dev;
+    spi_host_t *host;
+    spi_bus_lock_dev_handle_t dev_lock;
+};
+
+static spi_host_t* bus_driver_ctx[SOC_SPI_PERIPH_NUM] = {};
+
+static const char *SPI_TAG = "spi_master";
+#define SPI_CHECK(a, str, ret_val, ...) \
+    if (unlikely(!(a))) { \
+        ESP_LOGE(SPI_TAG,"%s(%d): "str, __FUNCTION__, __LINE__, ##__VA_ARGS__); \
+        return (ret_val); \
+    }
+
+
+static void spi_intr(void *arg);
+static void spi_bus_intr_enable(void *host);
+static void spi_bus_intr_disable(void *host);
+
+static esp_err_t spi_master_deinit_driver(void* arg);
+
+static inline bool is_valid_host(spi_host_device_t host)
+{
+//SPI1 can be used as GPSPI only on ESP32
+#if CONFIG_IDF_TARGET_ESP32
+    return host >= SPI1_HOST && host <= SPI3_HOST;
+#elif (SOC_SPI_PERIPH_NUM == 2)
+    return host == SPI2_HOST;
+#elif (SOC_SPI_PERIPH_NUM == 3)
+    return host >= SPI2_HOST && host <= SPI3_HOST;
+#endif
+}
+
+// Should be called before any devices are actually registered or used.
+// Currently automatically called after `spi_bus_initialize()` and when first device is registered.
+static esp_err_t spi_master_init_driver(spi_host_device_t host_id)
+{
+    esp_err_t err = ESP_OK;
+
+    const spi_bus_attr_t* bus_attr = spi_bus_get_attr(host_id);
+    SPI_CHECK(bus_attr != NULL, "host_id not initialized", ESP_ERR_INVALID_STATE);
+    SPI_CHECK(bus_attr->lock != NULL, "SPI Master cannot attach to bus. (Check CONFIG_SPI_FLASH_SHARE_SPI1_BUS)", ESP_ERR_INVALID_ARG);
+    // spihost contains atomic variables, which should not be put in PSRAM
+    spi_host_t* host = heap_caps_malloc(sizeof(spi_host_t), MALLOC_CAP_INTERNAL | MALLOC_CAP_8BIT);
+    if (host == NULL) {
+        err = ESP_ERR_NO_MEM;
+        goto cleanup;
+    }
+
+    *host = (spi_host_t) {
+        .id = host_id,
+        .cur_cs = DEV_NUM_MAX,
+        .polling = false,
+        .device_acquiring_lock = NULL,
+        .bus_attr = bus_attr,
+    };
+
+    if (host_id != SPI1_HOST) {
+        // interrupts are not allowed on SPI1 bus
+        err = esp_intr_alloc(spicommon_irqsource_for_host(host_id),
+                            bus_attr->bus_cfg.intr_flags | ESP_INTR_FLAG_INTRDISABLED,
+                            spi_intr, host, &host->intr);
+        if (err != ESP_OK) {
+            goto cleanup;
+        }
+    }
+
+    //assign the SPI, RX DMA and TX DMA peripheral registers beginning address
+    spi_hal_config_t hal_config = {
+        //On ESP32-S2 and earlier chips, DMA registers are part of SPI registers. Pass the registers of SPI peripheral to control it.
+        .dma_in = SPI_LL_GET_HW(host_id),
+        .dma_out = SPI_LL_GET_HW(host_id),
+        .dma_enabled = bus_attr->dma_enabled,
+        .dmadesc_tx = bus_attr->dmadesc_tx,
+        .dmadesc_rx = bus_attr->dmadesc_rx,
+        .tx_dma_chan = bus_attr->tx_dma_chan,
+        .rx_dma_chan = bus_attr->rx_dma_chan,
+        .dmadesc_n = bus_attr->dma_desc_num,
+    };
+    spi_hal_init(&host->hal, host_id, &hal_config);
+
+    if (host_id != SPI1_HOST) {
+        //SPI1 attributes are already initialized at start up.
+        spi_bus_lock_handle_t lock = spi_bus_lock_get_by_id(host_id);
+        spi_bus_lock_set_bg_control(lock, spi_bus_intr_enable, spi_bus_intr_disable, host);
+        spi_bus_register_destroy_func(host_id, spi_master_deinit_driver, host);
+    }
+
+    bus_driver_ctx[host_id] = host;
+    return ESP_OK;
+
+cleanup:
+    if (host) {
+        spi_hal_deinit(&host->hal);
+        if (host->intr) {
+            esp_intr_free(host->intr);
+        }
+    }
+    free(host);
+    return err;
+}
+
+static esp_err_t spi_master_deinit_driver(void* arg)
+{
+    spi_host_t *host = (spi_host_t*)arg;
+    SPI_CHECK(host != NULL, "host_id not in use", ESP_ERR_INVALID_STATE);
+
+    int host_id = host->id;
+    SPI_CHECK(is_valid_host(host_id), "invalid host_id", ESP_ERR_INVALID_ARG);
+
+    int x;
+    for (x=0; x<DEV_NUM_MAX; x++) {
+        SPI_CHECK(host->device[x] == NULL, "not all CSses freed", ESP_ERR_INVALID_STATE);
+    }
+
+    spi_hal_deinit(&host->hal);
+
+    if (host->intr) {
+        esp_intr_free(host->intr);
+    }
+    free(host);
+    bus_driver_ctx[host_id] = NULL;
+    return ESP_OK;
+}
+
+void spi_get_timing(bool gpio_is_used, int input_delay_ns, int eff_clk, int* dummy_o, int* cycles_remain_o)
+{
+    int timing_dummy;
+    int timing_miso_delay;
+
+    spi_hal_cal_timing(eff_clk, gpio_is_used, input_delay_ns, &timing_dummy, &timing_miso_delay);
+    if (dummy_o) *dummy_o = timing_dummy;
+    if (cycles_remain_o) *cycles_remain_o = timing_miso_delay;
+}
+
+int spi_get_freq_limit(bool gpio_is_used, int input_delay_ns)
+{
+    return spi_hal_get_freq_limit(gpio_is_used, input_delay_ns);
+}
+
+/*
+ Add a device. This allocates a CS line for the device, allocates memory for the device structure and hooks
+ up the CS pin to whatever is specified.
+*/
+esp_err_t spi_bus_add_device(spi_host_device_t host_id, const spi_device_interface_config_t *dev_config, spi_device_handle_t *handle)
+{
+    spi_device_t *dev = NULL;
+    esp_err_t err = ESP_OK;
+
+    SPI_CHECK(is_valid_host(host_id), "invalid host", ESP_ERR_INVALID_ARG);
+    if (bus_driver_ctx[host_id] == NULL) {
+        //lazy initialization the driver, get deinitialized by the bus is freed
+        err = spi_master_init_driver(host_id);
+        if (err != ESP_OK) {
+            return err;
+        }
+    }
+
+    spi_host_t *host = bus_driver_ctx[host_id];
+    const spi_bus_attr_t* bus_attr = host->bus_attr;
+    SPI_CHECK(dev_config->spics_io_num < 0 || GPIO_IS_VALID_OUTPUT_GPIO(dev_config->spics_io_num), "spics pin invalid", ESP_ERR_INVALID_ARG);
+    SPI_CHECK(dev_config->clock_speed_hz > 0, "invalid sclk speed", ESP_ERR_INVALID_ARG);
+#ifdef CONFIG_IDF_TARGET_ESP32
+    //The hardware looks like it would support this, but actually setting cs_ena_pretrans when transferring in full
+    //duplex mode does absolutely nothing on the ESP32.
+    SPI_CHECK(dev_config->cs_ena_pretrans <= 1 || (dev_config->address_bits == 0 && dev_config->command_bits == 0) ||
+        (dev_config->flags & SPI_DEVICE_HALFDUPLEX), "In full-duplex mode, only support cs pretrans delay = 1 and without address_bits and command_bits", ESP_ERR_INVALID_ARG);
+#endif
+    uint32_t lock_flag = ((dev_config->spics_io_num != -1)? SPI_BUS_LOCK_DEV_FLAG_CS_REQUIRED: 0);
+
+    spi_bus_lock_dev_config_t lock_config = {
+        .flags = lock_flag,
+    };
+    spi_bus_lock_dev_handle_t dev_handle;
+    err = spi_bus_lock_register_dev(bus_attr->lock, &lock_config, &dev_handle);
+    if (err != ESP_OK) {
+        goto nomem;
+    }
+
+    int freecs = spi_bus_lock_get_dev_id(dev_handle);
+    SPI_CHECK(freecs != -1, "no free cs pins for the host", ESP_ERR_NOT_FOUND);
+
+    //input parameters to calculate timing configuration
+    int half_duplex = dev_config->flags & SPI_DEVICE_HALFDUPLEX ? 1 : 0;
+    int no_compensate = dev_config->flags & SPI_DEVICE_NO_DUMMY ? 1 : 0;
+    int duty_cycle = (dev_config->duty_cycle_pos==0) ? 128 : dev_config->duty_cycle_pos;
+    int use_gpio = !(bus_attr->flags & SPICOMMON_BUSFLAG_IOMUX_PINS);
+    spi_hal_timing_param_t timing_param = {
+        .half_duplex = half_duplex,
+        .no_compensate = no_compensate,
+        .clock_speed_hz = dev_config->clock_speed_hz,
+        .duty_cycle = duty_cycle,
+        .input_delay_ns = dev_config->input_delay_ns,
+        .use_gpio = use_gpio
+    };
+
+    //output values of timing configuration
+    spi_hal_timing_conf_t temp_timing_conf;
+    int freq;
+    esp_err_t ret = spi_hal_cal_clock_conf(&timing_param, &freq, &temp_timing_conf);
+    SPI_CHECK(ret==ESP_OK, "assigned clock speed not supported", ret);
+
+    //Allocate memory for device
+    dev = malloc(sizeof(spi_device_t));
+    if (dev == NULL) goto nomem;
+    memset(dev, 0, sizeof(spi_device_t));
+
+    dev->id = freecs;
+    dev->dev_lock = dev_handle;
+
+    //Allocate queues, set defaults
+    dev->trans_queue = xQueueCreate(dev_config->queue_size, sizeof(spi_trans_priv_t));
+    dev->ret_queue = xQueueCreate(dev_config->queue_size, sizeof(spi_trans_priv_t));
+    if (!dev->trans_queue || !dev->ret_queue) {
+        goto nomem;
+    }
+
+    //We want to save a copy of the dev config in the dev struct.
+    memcpy(&dev->cfg, dev_config, sizeof(spi_device_interface_config_t));
+    dev->cfg.duty_cycle_pos = duty_cycle;
+    // TODO: if we have to change the apb clock among transactions, re-calculate this each time the apb clock lock is locked.
+
+    //Set CS pin, CS options
+    if (dev_config->spics_io_num >= 0) {
+        spicommon_cs_initialize(host_id, dev_config->spics_io_num, freecs, use_gpio);
+    }
+
+	// create a mutex if we have more than one client
+	if (host->count++) {
+		ESP_LOGI(SPI_TAG, "More than one device on SPI %d => creating mutex", host_id);
+		//host->mutex = xSemaphoreCreateMutex();
+	}
+
+    //save a pointer to device in spi_host_t
+    host->device[freecs] = dev;
+    //save a pointer to host in spi_device_t
+    dev->host= host;
+
+    //initialise the device specific configuration
+    spi_hal_dev_config_t *hal_dev = &(dev->hal_dev);
+    hal_dev->mode = dev_config->mode;
+    hal_dev->cs_setup = dev_config->cs_ena_pretrans;
+    hal_dev->cs_hold = dev_config->cs_ena_posttrans;
+    //set hold_time to 0 will not actually append delay to CS
+    //set it to 1 since we do need at least one clock of hold time in most cases
+    if (hal_dev->cs_hold == 0) {
+        hal_dev->cs_hold = 1;
+    }
+    hal_dev->cs_pin_id = dev->id;
+    hal_dev->timing_conf = temp_timing_conf;
+    hal_dev->sio = (dev_config->flags) & SPI_DEVICE_3WIRE ? 1 : 0;
+    hal_dev->half_duplex = dev_config->flags & SPI_DEVICE_HALFDUPLEX ? 1 : 0;
+    hal_dev->tx_lsbfirst = dev_config->flags & SPI_DEVICE_TXBIT_LSBFIRST ? 1 : 0;
+    hal_dev->rx_lsbfirst = dev_config->flags & SPI_DEVICE_RXBIT_LSBFIRST ? 1 : 0;
+    hal_dev->no_compensate = dev_config->flags & SPI_DEVICE_NO_DUMMY ? 1 : 0;
+#if SOC_SPI_SUPPORT_AS_CS
+    hal_dev->as_cs = dev_config->flags& SPI_DEVICE_CLK_AS_CS ? 1 : 0;
+#endif
+    hal_dev->positive_cs = dev_config->flags & SPI_DEVICE_POSITIVE_CS ? 1 : 0;
+
+    *handle = dev;
+    ESP_LOGD(SPI_TAG, "SPI%d: New device added to CS%d, effective clock: %dkHz", host_id+1, freecs, freq/1000);
+
+    return ESP_OK;
+
+nomem:
+    if (dev) {
+        if (dev->trans_queue) vQueueDelete(dev->trans_queue);
+        if (dev->ret_queue) vQueueDelete(dev->ret_queue);
+        spi_bus_lock_unregister_dev(dev->dev_lock);
+    }
+    free(dev);
+    return ESP_ERR_NO_MEM;
+}
+
+esp_err_t spi_bus_remove_device(spi_device_handle_t handle)
+{
+    SPI_CHECK(handle!=NULL, "invalid handle", ESP_ERR_INVALID_ARG);
+    //These checks aren't exhaustive; another thread could sneak in a transaction inbetween. These are only here to
+    //catch design errors and aren't meant to be triggered during normal operation.
+    SPI_CHECK(uxQueueMessagesWaiting(handle->trans_queue)==0, "Have unfinished transactions", ESP_ERR_INVALID_STATE);
+    SPI_CHECK(handle->host->cur_cs == DEV_NUM_MAX || handle->host->device[handle->host->cur_cs] != handle, "Have unfinished transactions", ESP_ERR_INVALID_STATE);
+    SPI_CHECK(uxQueueMessagesWaiting(handle->ret_queue)==0, "Have unfinished transactions", ESP_ERR_INVALID_STATE);
+
+    //return
+    int spics_io_num = handle->cfg.spics_io_num;
+    if (spics_io_num >= 0) spicommon_cs_free_io(spics_io_num);
+
+    //Kill queues
+    vQueueDelete(handle->trans_queue);
+    vQueueDelete(handle->ret_queue);
+    spi_bus_lock_unregister_dev(handle->dev_lock);
+
+    assert(handle->host->device[handle->id] == handle);
+    handle->host->device[handle->id] = NULL;
+    free(handle);
+    return ESP_OK;
+}
+
+int spi_cal_clock(int fapb, int hz, int duty_cycle, uint32_t *reg_o)
+{
+    return spi_ll_master_cal_clock(fapb, hz, duty_cycle, reg_o);
+}
+
+int spi_get_actual_clock(int fapb, int hz, int duty_cycle)
+{
+    return spi_hal_master_cal_clock(fapb, hz, duty_cycle);
+}
+
+// Setup the device-specified configuration registers. Called every time a new
+// transaction is to be sent, but only apply new configurations when the device
+// changes.
+static SPI_MASTER_ISR_ATTR void spi_setup_device(spi_device_t *dev)
+{
+    spi_bus_lock_dev_handle_t dev_lock = dev->dev_lock;
+
+    if (!spi_bus_lock_touch(dev_lock)) {
+        //if the configuration is already applied, skip the following.
+        return;
+    }
+    spi_hal_context_t *hal = &dev->host->hal;
+    spi_hal_dev_config_t *hal_dev = &(dev->hal_dev);
+    spi_hal_setup_device(hal, hal_dev);
+}
+
+static SPI_MASTER_ISR_ATTR spi_device_t *get_acquiring_dev(spi_host_t *host)
+{
+    spi_bus_lock_dev_handle_t dev_lock = spi_bus_lock_get_acquiring_dev(host->bus_attr->lock);
+if (!dev_lock) {
+ESP_LOGW(SPI_TAG, "NOBODY HERE");
+return NULL;
+}	
+
+    return host->device[spi_bus_lock_get_dev_id(dev_lock)];
+}
+
+// Debug only
+// NOTE if the acquiring is not fully completed, `spi_bus_lock_get_acquiring_dev`
+// may return a false `NULL` cause the function returning false `false`.
+static inline SPI_MASTER_ISR_ATTR bool spi_bus_device_is_polling(spi_device_t *dev)
+{
+spi_device_t *toto = NULL;
+spi_bus_lock_dev_handle_t dev_lock = spi_bus_lock_get_acquiring_dev(dev->host->bus_attr->lock);
+if (dev_lock) toto = dev->host->device[spi_bus_lock_get_dev_id(dev_lock)];
+return toto == dev && dev->host->polling;
+	
+    //return get_acquiring_dev(dev->host) == dev && dev->host->polling;
+}
+
+/*-----------------------------------------------------------------------------
+    Working Functions
+-----------------------------------------------------------------------------*/
+
+// The interrupt may get invoked by the bus lock.
+static void SPI_MASTER_ISR_ATTR spi_bus_intr_enable(void *host)
+{
+    esp_intr_enable(((spi_host_t*)host)->intr);
+}
+
+// The interrupt is always disabled by the ISR itself, not exposed
+static void SPI_MASTER_ISR_ATTR spi_bus_intr_disable(void *host)
+{
+    esp_intr_disable(((spi_host_t*)host)->intr);
+}
+
+// The function is called to send a new transaction, in ISR or in the task.
+// Setup the transaction-specified registers and linked-list used by the DMA (or FIFO if DMA is not used)
+static void SPI_MASTER_ISR_ATTR spi_new_trans(spi_device_t *dev, spi_trans_priv_t *trans_buf)
+{
+    spi_transaction_t *trans = NULL;
+    spi_host_t *host = dev->host;
+    spi_hal_context_t *hal = &(host->hal);
+    spi_hal_dev_config_t *hal_dev = &(dev->hal_dev);
+
+    trans = trans_buf->trans;
+    host->cur_cs = dev->id;
+
+    //Reconfigure according to device settings, the function only has effect when the dev_id is changed.
+    spi_setup_device(dev);
+
+    //set the transaction specific configuration each time before a transaction setup
+    spi_hal_trans_config_t hal_trans = {};
+    hal_trans.tx_bitlen = trans->length;
+    hal_trans.rx_bitlen = trans->rxlength;
+    hal_trans.rcv_buffer = (uint8_t*)host->cur_trans_buf.buffer_to_rcv;
+    hal_trans.send_buffer = (uint8_t*)host->cur_trans_buf.buffer_to_send;
+    hal_trans.cmd = trans->cmd;
+    hal_trans.addr = trans->addr;
+    //Set up QIO/DIO if needed
+    hal_trans.io_mode = (trans->flags & SPI_TRANS_MODE_DIO ?
+                        (trans->flags & SPI_TRANS_MODE_DIOQIO_ADDR ? SPI_LL_IO_MODE_DIO : SPI_LL_IO_MODE_DUAL) :
+                    (trans->flags & SPI_TRANS_MODE_QIO ?
+                        (trans->flags & SPI_TRANS_MODE_DIOQIO_ADDR ? SPI_LL_IO_MODE_QIO : SPI_LL_IO_MODE_QUAD) :
+                    SPI_LL_IO_MODE_NORMAL
+                    ));
+
+    if (trans->flags & SPI_TRANS_VARIABLE_CMD) {
+        hal_trans.cmd_bits = ((spi_transaction_ext_t *)trans)->command_bits;
+    } else {
+        hal_trans.cmd_bits = dev->cfg.command_bits;
+    }
+    if (trans->flags & SPI_TRANS_VARIABLE_ADDR) {
+        hal_trans.addr_bits = ((spi_transaction_ext_t *)trans)->address_bits;
+    } else {
+        hal_trans.addr_bits = dev->cfg.address_bits;
+    }
+    if (trans->flags & SPI_TRANS_VARIABLE_DUMMY) {
+        hal_trans.dummy_bits = ((spi_transaction_ext_t *)trans)->dummy_bits;
+    } else {
+        hal_trans.dummy_bits = dev->cfg.dummy_bits;
+    }
+
+    spi_hal_setup_trans(hal, hal_dev, &hal_trans);
+    spi_hal_prepare_data(hal, hal_dev, &hal_trans);
+
+    //Call pre-transmission callback, if any
+    if (dev->cfg.pre_cb) dev->cfg.pre_cb(trans);
+    //Kick off transfer
+    spi_hal_user_start(hal);
+}
+
+// The function is called when a transaction is done, in ISR or in the task.
+// Fetch the data from FIFO and call the ``post_cb``.
+static void SPI_MASTER_ISR_ATTR spi_post_trans(spi_host_t *host)
+{
+    spi_transaction_t *cur_trans = host->cur_trans_buf.trans;
+
+    spi_hal_fetch_result(&host->hal);
+    //Call post-transaction callback, if any
+    spi_device_t* dev = host->device[host->cur_cs];
+    if (dev->cfg.post_cb) dev->cfg.post_cb(cur_trans);
+
+    host->cur_cs = DEV_NUM_MAX;
+}
+
+// This is run in interrupt context.
+static void SPI_MASTER_ISR_ATTR spi_intr(void *arg)
+{
+    BaseType_t do_yield = pdFALSE;
+    spi_host_t *host = (spi_host_t *)arg;
+    const spi_bus_attr_t* bus_attr = host->bus_attr;
+
+    assert(spi_hal_usr_is_done(&host->hal));
+
+    /*
+     * Help to skip the handling of in-flight transaction, and disable of the interrupt.
+     * The esp_intr_enable will be called (b) after new BG request is queued (a) in the task;
+     * while esp_intr_disable should be called (c) if we check and found the sending queue is empty (d).
+     * If (c) is called after (d), then there is a risk that things happens in this sequence:
+     * (d) -> (a) -> (b) -> (c), and in this case the interrupt is disabled while there's pending BG request in the queue.
+     * To avoid this, interrupt is disabled here, and re-enabled later if required.
+     */
+    if (!spi_bus_lock_bg_entry(bus_attr->lock)) {
+        /*------------ deal with the in-flight transaction -----------------*/
+        assert(host->cur_cs != DEV_NUM_MAX);
+        //Okay, transaction is done.
+        const int cs = host->cur_cs;
+        //Tell common code DMA workaround that our DMA channel is idle. If needed, the code will do a DMA reset.
+        if (bus_attr->dma_enabled) {
+            //This workaround is only for esp32, where tx_dma_chan and rx_dma_chan are always same
+            spicommon_dmaworkaround_idle(bus_attr->tx_dma_chan);
+        }
+
+        //cur_cs is changed to DEV_NUM_MAX here
+        spi_post_trans(host);
+        // spi_bus_lock_bg_pause(bus_attr->lock);
+        //Return transaction descriptor.
+        xQueueSendFromISR(host->device[cs]->ret_queue, &host->cur_trans_buf, &do_yield);
+#ifdef CONFIG_PM_ENABLE
+        //Release APB frequency lock
+        esp_pm_lock_release(bus_attr->pm_lock);
+#endif
+    }
+
+    /*------------ new transaction starts here ------------------*/
+    assert(host->cur_cs == DEV_NUM_MAX);
+
+    spi_bus_lock_handle_t lock = host->bus_attr->lock;
+    BaseType_t trans_found = pdFALSE;
+
+
+    // There should be remaining requests
+    BUS_LOCK_DEBUG_EXECUTE_CHECK(spi_bus_lock_bg_req_exist(lock));
+
+    do {
+        spi_bus_lock_dev_handle_t acq_dev_lock = spi_bus_lock_get_acquiring_dev(lock);
+        spi_bus_lock_dev_handle_t desired_dev = acq_dev_lock;
+        bool resume_task = false;
+        spi_device_t* device_to_send = NULL;
+
+        if (!acq_dev_lock) {
+            // This function may assign a new acquiring device, otherwise it will suggest a desired device with BG active
+            // We use either of them without further searching in the devices.
+            // If the return value is true, it means either there's no acquiring device, or the acquiring device's BG is active,
+            // We stay in the ISR to deal with those transactions of desired device, otherwise nothing will be done, check whether we need to resume some other tasks, or just quit the ISR
+            resume_task = spi_bus_lock_bg_check_dev_acq(lock, &desired_dev);
+        }
+
+        if (!resume_task) {
+            bool dev_has_req = spi_bus_lock_bg_check_dev_req(desired_dev);
+            if (dev_has_req) {
+                device_to_send = host->device[spi_bus_lock_get_dev_id(desired_dev)];
+                trans_found = xQueueReceiveFromISR(device_to_send->trans_queue, &host->cur_trans_buf, &do_yield);
+                if (!trans_found) {
+                    spi_bus_lock_bg_clear_req(desired_dev);
+                }
+            }
+        }
+
+        if (trans_found) {
+            spi_trans_priv_t *const cur_trans_buf = &host->cur_trans_buf;
+            if (bus_attr->dma_enabled && (cur_trans_buf->buffer_to_rcv || cur_trans_buf->buffer_to_send)) {
+                //mark channel as active, so that the DMA will not be reset by the slave
+                //This workaround is only for esp32, where tx_dma_chan and rx_dma_chan are always same
+                spicommon_dmaworkaround_transfer_active(bus_attr->tx_dma_chan);
+            }
+            spi_new_trans(device_to_send, cur_trans_buf);
+        }
+        // Exit of the ISR, handle interrupt re-enable (if sending transaction), retry (if there's coming BG),
+        // or resume acquiring device task (if quit due to bus acquiring).
+    } while (!spi_bus_lock_bg_exit(lock, trans_found, &do_yield));
+
+    if (do_yield) portYIELD_FROM_ISR();
+}
+
+static SPI_MASTER_ISR_ATTR esp_err_t check_trans_valid(spi_device_handle_t handle, spi_transaction_t *trans_desc)
+{
+    SPI_CHECK(handle!=NULL, "invalid dev handle", ESP_ERR_INVALID_ARG);
+    spi_host_t *host = handle->host;
+    const spi_bus_attr_t* bus_attr = host->bus_attr;
+    bool tx_enabled = (trans_desc->flags & SPI_TRANS_USE_TXDATA) || (trans_desc->tx_buffer);
+    bool rx_enabled = (trans_desc->flags & SPI_TRANS_USE_RXDATA) || (trans_desc->rx_buffer);
+    spi_transaction_ext_t *t_ext = (spi_transaction_ext_t *)trans_desc;
+    bool dummy_enabled = (((trans_desc->flags & SPI_TRANS_VARIABLE_DUMMY)? t_ext->dummy_bits: handle->cfg.dummy_bits) != 0);
+    bool extra_dummy_enabled = handle->hal_dev.timing_conf.timing_dummy;
+    bool is_half_duplex = ((handle->cfg.flags & SPI_DEVICE_HALFDUPLEX) != 0);
+
+    //check transmission length
+    SPI_CHECK((trans_desc->flags & SPI_TRANS_USE_RXDATA)==0 || trans_desc->rxlength <= 32, "SPI_TRANS_USE_RXDATA only available for rxdata transfer <= 32 bits", ESP_ERR_INVALID_ARG);
+    SPI_CHECK((trans_desc->flags & SPI_TRANS_USE_TXDATA)==0 || trans_desc->length <= 32, "SPI_TRANS_USE_TXDATA only available for txdata transfer <= 32 bits", ESP_ERR_INVALID_ARG);
+    SPI_CHECK(trans_desc->length <= bus_attr->max_transfer_sz*8, "txdata transfer > host maximum", ESP_ERR_INVALID_ARG);
+    SPI_CHECK(trans_desc->rxlength <= bus_attr->max_transfer_sz*8, "rxdata transfer > host maximum", ESP_ERR_INVALID_ARG);
+    SPI_CHECK(is_half_duplex || trans_desc->rxlength <= trans_desc->length, "rx length > tx length in full duplex mode", ESP_ERR_INVALID_ARG);
+    //check working mode
+    SPI_CHECK(!((trans_desc->flags & (SPI_TRANS_MODE_DIO|SPI_TRANS_MODE_QIO)) && (handle->cfg.flags & SPI_DEVICE_3WIRE)), "incompatible iface params", ESP_ERR_INVALID_ARG);
+    SPI_CHECK(!((trans_desc->flags & (SPI_TRANS_MODE_DIO|SPI_TRANS_MODE_QIO)) && !is_half_duplex), "incompatible iface params", ESP_ERR_INVALID_ARG);
+#ifdef CONFIG_IDF_TARGET_ESP32
+    SPI_CHECK(!is_half_duplex || !bus_attr->dma_enabled || !rx_enabled || !tx_enabled, "SPI half duplex mode does not support using DMA with both MOSI and MISO phases.", ESP_ERR_INVALID_ARG );
+#elif CONFIG_IDF_TARGET_ESP32S3
+    SPI_CHECK(!is_half_duplex || !tx_enabled || !rx_enabled, "SPI half duplex mode is not supported when both MOSI and MISO phases are enabled.", ESP_ERR_INVALID_ARG);
+#endif
+    //MOSI phase is skipped only when both tx_buffer and SPI_TRANS_USE_TXDATA are not set.
+    SPI_CHECK(trans_desc->length != 0 || !tx_enabled, "trans tx_buffer should be NULL and SPI_TRANS_USE_TXDATA should be cleared to skip MOSI phase.", ESP_ERR_INVALID_ARG);
+    //MISO phase is skipped only when both rx_buffer and SPI_TRANS_USE_RXDATA are not set.
+    //If set rxlength=0 in full_duplex mode, it will be automatically set to length
+    SPI_CHECK(!is_half_duplex || trans_desc->rxlength != 0 || !rx_enabled, "trans rx_buffer should be NULL and SPI_TRANS_USE_RXDATA should be cleared to skip MISO phase.", ESP_ERR_INVALID_ARG);
+    //In Full duplex mode, default rxlength to be the same as length, if not filled in.
+    // set rxlength to length is ok, even when rx buffer=NULL
+    if (trans_desc->rxlength==0 && !is_half_duplex) {
+        trans_desc->rxlength=trans_desc->length;
+    }
+    //Dummy phase is not available when both data out and in are enabled, regardless of FD or HD mode.
+    SPI_CHECK(!tx_enabled || !rx_enabled || !dummy_enabled || !extra_dummy_enabled, "Dummy phase is not available when both data out and in are enabled", ESP_ERR_INVALID_ARG);
+
+    return ESP_OK;
+}
+
+static SPI_MASTER_ISR_ATTR void uninstall_priv_desc(spi_trans_priv_t* trans_buf)
+{
+    spi_transaction_t *trans_desc = trans_buf->trans;
+    if ((void *)trans_buf->buffer_to_send != &trans_desc->tx_data[0] &&
+        trans_buf->buffer_to_send != trans_desc->tx_buffer) {
+        free((void *)trans_buf->buffer_to_send); //force free, ignore const
+    }
+    // copy data from temporary DMA-capable buffer back to IRAM buffer and free the temporary one.
+    if ((void *)trans_buf->buffer_to_rcv != &trans_desc->rx_data[0] &&
+        trans_buf->buffer_to_rcv != trans_desc->rx_buffer) { // NOLINT(clang-analyzer-unix.Malloc)
+        if (trans_desc->flags & SPI_TRANS_USE_RXDATA) {
+            memcpy((uint8_t *) & trans_desc->rx_data[0], trans_buf->buffer_to_rcv, (trans_desc->rxlength + 7) / 8);
+        } else {
+            memcpy(trans_desc->rx_buffer, trans_buf->buffer_to_rcv, (trans_desc->rxlength + 7) / 8);
+        }
+        free(trans_buf->buffer_to_rcv);
+    }
+}
+
+static SPI_MASTER_ISR_ATTR esp_err_t setup_priv_desc(spi_transaction_t *trans_desc, spi_trans_priv_t* new_desc, bool isdma)
+{
+    *new_desc = (spi_trans_priv_t) { .trans = trans_desc, };
+
+    // rx memory assign
+    uint32_t* rcv_ptr;
+    if ( trans_desc->flags & SPI_TRANS_USE_RXDATA ) {
+        rcv_ptr = (uint32_t *)&trans_desc->rx_data[0];
+    } else {
+        //if not use RXDATA neither rx_buffer, buffer_to_rcv assigned to NULL
+        rcv_ptr = trans_desc->rx_buffer;
+    }
+    if (rcv_ptr && isdma && (!esp_ptr_dma_capable(rcv_ptr) || ((int)rcv_ptr % 4 != 0))) {
+        //if rxbuf in the desc not DMA-capable, malloc a new one. The rx buffer need to be length of multiples of 32 bits to avoid heap corruption.
+        ESP_LOGD(SPI_TAG, "Allocate RX buffer for DMA" );
+        rcv_ptr = heap_caps_malloc((trans_desc->rxlength + 31) / 8, MALLOC_CAP_DMA);
+        if (rcv_ptr == NULL) goto clean_up;
+    }
+    new_desc->buffer_to_rcv = rcv_ptr;
+
+    // tx memory assign
+    const uint32_t *send_ptr;
+    if ( trans_desc->flags & SPI_TRANS_USE_TXDATA ) {
+        send_ptr = (uint32_t *)&trans_desc->tx_data[0];
+    } else {
+        //if not use TXDATA neither tx_buffer, tx data assigned to NULL
+        send_ptr = trans_desc->tx_buffer ;
+    }
+    if (send_ptr && isdma && !esp_ptr_dma_capable( send_ptr )) {
+        //if txbuf in the desc not DMA-capable, malloc a new one
+        ESP_LOGD(SPI_TAG, "Allocate TX buffer for DMA" );
+        uint32_t *temp = heap_caps_malloc((trans_desc->length + 7) / 8, MALLOC_CAP_DMA);
+        if (temp == NULL) goto clean_up;
+
+        memcpy( temp, send_ptr, (trans_desc->length + 7) / 8 );
+        send_ptr = temp;
+    }
+    new_desc->buffer_to_send = send_ptr;
+
+    return ESP_OK;
+
+clean_up:
+    uninstall_priv_desc(new_desc);
+    return ESP_ERR_NO_MEM;
+}
+
+esp_err_t SPI_MASTER_ATTR spi_device_queue_trans(spi_device_handle_t handle, spi_transaction_t *trans_desc, TickType_t ticks_to_wait)
+{
+    esp_err_t ret = check_trans_valid(handle, trans_desc);
+    if (ret != ESP_OK) return ret;
+
+    spi_host_t *host = handle->host;
+
+    SPI_CHECK(!spi_bus_device_is_polling(handle), "Cannot queue new transaction while previous polling transaction is not terminated.", ESP_ERR_INVALID_STATE );
+
+    spi_trans_priv_t trans_buf;
+    ret = setup_priv_desc(trans_desc, &trans_buf, (host->bus_attr->dma_enabled));
+    if (ret != ESP_OK) return ret;
+
+#ifdef CONFIG_PM_ENABLE
+    esp_pm_lock_acquire(host->bus_attr->pm_lock);
+#endif
+    //Send to queue and invoke the ISR.
+
+    BaseType_t r = xQueueSend(handle->trans_queue, (void *)&trans_buf, ticks_to_wait);
+    if (!r) {
+        ret = ESP_ERR_TIMEOUT;
+#ifdef CONFIG_PM_ENABLE
+        //Release APB frequency lock
+        esp_pm_lock_release(host->bus_attr->pm_lock);
+#endif
+        goto clean_up;
+    }
+
+    // The ISR will be invoked at correct time by the lock with `spi_bus_intr_enable`.
+    ret = spi_bus_lock_bg_request(handle->dev_lock);
+    if (ret != ESP_OK) {
+        goto clean_up;
+    }
+    return ESP_OK;
+
+clean_up:
+    uninstall_priv_desc(&trans_buf);
+    return ret;
+}
+
+esp_err_t SPI_MASTER_ATTR spi_device_get_trans_result(spi_device_handle_t handle, spi_transaction_t **trans_desc, TickType_t ticks_to_wait)
+{
+    BaseType_t r;
+    spi_trans_priv_t trans_buf;
+    SPI_CHECK(handle!=NULL, "invalid dev handle", ESP_ERR_INVALID_ARG);
+
+    //use the interrupt, block until return
+    r=xQueueReceive(handle->ret_queue, (void*)&trans_buf, ticks_to_wait);
+    if (!r) {
+        // The memory occupied by rx and tx DMA buffer destroyed only when receiving from the queue (transaction finished).
+        // If timeout, wait and retry.
+        // Every in-flight transaction request occupies internal memory as DMA buffer if needed.
+        return ESP_ERR_TIMEOUT;
+    }
+    //release temporary buffers
+    uninstall_priv_desc(&trans_buf);
+    (*trans_desc) = trans_buf.trans;
+
+    return ESP_OK;
+}
+
+//Porcelain to do one blocking transmission.
+esp_err_t SPI_MASTER_ATTR spi_device_transmit(spi_device_handle_t handle, spi_transaction_t *trans_desc)
+{
+    esp_err_t ret;
+    spi_transaction_t *ret_trans;
+    //ToDo: check if any spi transfers in flight
+    ret = spi_device_queue_trans(handle, trans_desc, portMAX_DELAY);
+    if (ret != ESP_OK) return ret;
+
+    ret = spi_device_get_trans_result(handle, &ret_trans, portMAX_DELAY);
+    if (ret != ESP_OK) return ret;
+
+    assert(ret_trans == trans_desc);
+    return ESP_OK;
+}
+
+esp_err_t SPI_MASTER_ISR_ATTR spi_device_acquire_bus(spi_device_t *device, TickType_t wait)
+{
+    spi_host_t *const host = device->host;
+    SPI_CHECK(wait==portMAX_DELAY, "acquire finite time not supported now.", ESP_ERR_INVALID_ARG);
+    SPI_CHECK(!spi_bus_device_is_polling(device), "Cannot acquire bus when a polling transaction is in progress.", ESP_ERR_INVALID_STATE );
+
+    esp_err_t ret = spi_bus_lock_acquire_start(device->dev_lock, wait);
+    if (ret != ESP_OK) {
+        return ret;
+    }
+    host->device_acquiring_lock = device;
+
+    ESP_LOGD(SPI_TAG, "device%d locked the bus", device->id);
+
+#ifdef CONFIG_PM_ENABLE
+    // though we don't suggest to block the task before ``release_bus``, still allow doing so.
+    // this keeps the spi clock at 80MHz even if all tasks are blocked
+    esp_pm_lock_acquire(host->bus_attr->pm_lock);
+#endif
+    //configure the device ahead so that we don't need to do it again in the following transactions
+    spi_setup_device(host->device[device->id]);
+    //the DMA is also occupied by the device, all the slave devices that using DMA should wait until bus released.
+    if (host->bus_attr->dma_enabled) {
+        //This workaround is only for esp32, where tx_dma_chan and rx_dma_chan are always same
+        spicommon_dmaworkaround_transfer_active(host->bus_attr->tx_dma_chan);
+    }
+    return ESP_OK;
+}
+
+// This function restore configurations required in the non-polling mode
+void SPI_MASTER_ISR_ATTR spi_device_release_bus(spi_device_t *dev)
+{
+    spi_host_t *host = dev->host;
+
+    if (spi_bus_device_is_polling(dev)){
+        ESP_EARLY_LOGE(SPI_TAG, "Cannot release bus when a polling transaction is in progress.");
+        assert(0);
+    }
+
+    if (host->bus_attr->dma_enabled) {
+        //This workaround is only for esp32, where tx_dma_chan and rx_dma_chan are always same
+        spicommon_dmaworkaround_idle(host->bus_attr->tx_dma_chan);
+    }
+    //Tell common code DMA workaround that our DMA channel is idle. If needed, the code will do a DMA reset.
+
+    //allow clock to be lower than 80MHz when all tasks blocked
+#ifdef CONFIG_PM_ENABLE
+    //Release APB frequency lock
+    esp_pm_lock_release(host->bus_attr->pm_lock);
+#endif
+    ESP_LOGD(SPI_TAG, "device%d release bus", dev->id);
+
+    host->device_acquiring_lock = NULL;
+    esp_err_t ret = spi_bus_lock_acquire_end(dev->dev_lock);
+    assert(ret == ESP_OK);
+}
+
+esp_err_t SPI_MASTER_ISR_ATTR spi_device_polling_start(spi_device_handle_t handle, spi_transaction_t *trans_desc, TickType_t ticks_to_wait)
+{
+    esp_err_t ret;
+    SPI_CHECK(ticks_to_wait == portMAX_DELAY, "currently timeout is not available for polling transactions", ESP_ERR_INVALID_ARG);
+    ret = check_trans_valid(handle, trans_desc);
+    if (ret!=ESP_OK) return ret;
+    SPI_CHECK(!spi_bus_device_is_polling(handle), "Cannot send polling transaction while the previous polling transaction is not terminated.", ESP_ERR_INVALID_STATE );
+
+    /* If device_acquiring_lock is set to handle, it means that the user has already
+     * acquired the bus thanks to the function `spi_device_acquire_bus()`.
+     * In that case, we don't need to take the lock again. */
+    spi_host_t *host = handle->host;
+try_again:	
+    if (host->device_acquiring_lock != handle) {
+        ret = spi_bus_lock_acquire_start(handle->dev_lock, ticks_to_wait);
+    } else {
+ESP_LOGW(SPI_TAG, "ALREADYA CQUIRED %d", handle->id);						
+        ret = spi_bus_lock_wait_bg_done(handle->dev_lock, ticks_to_wait);
+    }
+    if (ret != ESP_OK) return ret;
+	
+if (handle != get_acquiring_dev(host)) {
+ESP_LOGW(SPI_TAG, "WE THOUGHT WE ACQUIRED THE BUS %d %p", handle->id, host);						
+goto try_again;
+}	
+
+    ret = setup_priv_desc(trans_desc, &host->cur_trans_buf, (host->bus_attr->dma_enabled));
+    if (ret!=ESP_OK) return ret;
+
+    //Polling, no interrupt is used.
+    host->polling = true;
+
+    ESP_LOGV(SPI_TAG, "polling trans");
+    spi_new_trans(handle, &host->cur_trans_buf);
+
+    return ESP_OK;
+}
+
+esp_err_t SPI_MASTER_ISR_ATTR spi_device_polling_end(spi_device_handle_t handle, TickType_t ticks_to_wait)
+{
+    SPI_CHECK(handle != NULL, "invalid dev handle", ESP_ERR_INVALID_ARG);
+    spi_host_t *host = handle->host;
+
+    assert(host->cur_cs == handle->id);
+if (handle != get_acquiring_dev(host)) {
+spi_device_handle_t toto = get_acquiring_dev(host);
+ESP_LOGW(SPI_TAG, "SPIDEVICEHANDLE id %d (%d) , host %p (%p)", handle->id, toto ? toto->id : -1, handle->host, toto ? toto->host : NULL);
+}
+    assert(handle == get_acquiring_dev(host));
+
+    TickType_t start = xTaskGetTickCount();
+    while (!spi_hal_usr_is_done(&host->hal)) {
+        TickType_t end = xTaskGetTickCount();
+        if (end - start > ticks_to_wait) {
+            return ESP_ERR_TIMEOUT;
+        }
+    }
+
+    ESP_LOGV(SPI_TAG, "polling trans done");
+    //deal with the in-flight transaction
+    spi_post_trans(host);
+    //release temporary buffers
+    uninstall_priv_desc(&host->cur_trans_buf);
+
+    host->polling = false;
+    if (host->device_acquiring_lock != handle) {
+        assert(host->device_acquiring_lock == NULL);
+        spi_bus_lock_acquire_end(handle->dev_lock);
+    }
+
+    return ESP_OK;
+}
+
+esp_err_t SPI_MASTER_ISR_ATTR spi_device_polling_transmit(spi_device_handle_t handle, spi_transaction_t* trans_desc)
+{
+    esp_err_t ret;
+static struct {
+int count;
+SemaphoreHandle_t mutex;
+} ctx[4];
+int id = handle->id;
+ctx[id].count++;
+//if (!ctx[id].mutex) ctx[id].mutex = xSemaphoreCreateMutex();
+//xSemaphoreTake(ctx[id].mutex, portMAX_DELAY);
+if (handle->host->mutex) xSemaphoreTake(handle->host->mutex, portMAX_DELAY);
+if (ctx[id].count > 1) {
+ESP_LOGW(SPI_TAG, "COUNTER of %d is %d %p", id, ctx[id].count, handle->host);
+}
+
+    ret = spi_device_polling_start(handle, trans_desc, portMAX_DELAY);
+if (ctx[id].count > 1) {
+ESP_LOGW(SPI_TAG, "COUNTER of %d REALLY %d %p", id, ctx[id].count, handle->host);
+}	
+    //if (ret != ESP_OK) return ret;
+if (ret != ESP_OK) {
+ctx[id].count--;
+ESP_LOGE(SPI_TAG, "CAN'T START SPI POLLING %d", id);
+//	xSemaphoreGive(ctx[id].mutex);
+if (handle->host->mutex) xSemaphoreGive(handle->host->mutex);
+return ret;	
+}	
+
+ret = spi_device_polling_end(handle, portMAX_DELAY);
+ctx[id].count--;
+//xSemaphoreGive(ctx[id].mutex);
+if (handle->host->mutex) xSemaphoreGive(handle->host->mutex);
+return ret;
+//    return spi_device_polling_end(handle, portMAX_DELAY);
+}

+ 5 - 3
components/driver_bt/CMakeLists.txt

@@ -1,6 +1,8 @@
-idf_component_register(	SRC_DIRS .
-						INCLUDE_DIRS .
-						PRIV_REQUIRES services bt display console tools platform_config
+if(IDF_TARGET STREQUAL "esp32")
+    idf_component_register(	SRC_DIRS .
+                            INCLUDE_DIRS .
+                            PRIV_REQUIRES services bt display console tools platform_config
 
 )
+endif()
 

+ 172 - 0
components/driver_bt/bt_app_core - Copy.c.old

@@ -0,0 +1,172 @@
+/*
+   This example code is in the Public Domain (or CC0 licensed, at your option.)
+
+   Unless required by applicable law or agreed to in writing, this
+   software is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR
+   CONDITIONS OF ANY KIND, either express or implied.
+*/
+
+#include <stdint.h>
+#include <string.h>
+#include <stdbool.h>
+#include "esp_log.h"
+#include "freertos/FreeRTOS.h"
+#include "freertos/queue.h"
+#include "freertos/task.h"
+#include "esp_bt.h"
+#include "esp_bt_main.h"
+#include "esp_gap_bt_api.h"
+#include "bt_app_core.h"
+#include "tools.h"
+
+static const char *TAG = "btappcore";
+
+static void bt_app_task_handler(void *arg);
+static bool bt_app_send_msg(bt_app_msg_t *msg);
+static void bt_app_work_dispatched(bt_app_msg_t *msg);
+
+static xQueueHandle s_bt_app_task_queue;
+static bool running;
+
+bool bt_app_work_dispatch(bt_app_cb_t p_cback, uint16_t event, void *p_params, int param_len, bt_app_copy_cb_t p_copy_cback)
+{
+	ESP_LOGV(TAG,"%s event 0x%x, param len %d", __func__, event, param_len);
+
+    bt_app_msg_t msg;
+    memset(&msg, 0, sizeof(bt_app_msg_t));
+
+    msg.sig = BT_APP_SIG_WORK_DISPATCH;
+    msg.event = event;
+    msg.cb = p_cback;
+
+    if (param_len == 0) {
+        return bt_app_send_msg(&msg);
+    } else if (p_params && param_len > 0) {
+        if ((msg.param = clone_obj_psram(p_params, param_len)) != NULL) {
+            /* check if caller has provided a copy callback to do the deep copy */
+            if (p_copy_cback) {
+                p_copy_cback(&msg, msg.param, p_params);
+            }
+            return bt_app_send_msg(&msg);
+        }
+    }
+
+    return false;
+}
+
+static bool bt_app_send_msg(bt_app_msg_t *msg)
+{
+    if (msg == NULL) {
+        return false;
+    }
+
+    if (xQueueSend(s_bt_app_task_queue, msg, 10 / portTICK_RATE_MS) != pdTRUE) {
+    	ESP_LOGE(TAG,"%s xQueue send failed", __func__);
+        return false;
+    }
+    return true;
+}
+
+static void bt_app_work_dispatched(bt_app_msg_t *msg)
+{
+    if (msg->cb) {
+        msg->cb(msg->event, msg->param);
+    }
+}
+
+static void bt_app_task_handler(void *arg)
+{
+    bt_app_msg_t msg;
+	esp_err_t err;
+	
+	s_bt_app_task_queue = xQueueCreate(10, sizeof(bt_app_msg_t));
+	
+	esp_bt_controller_mem_release(ESP_BT_MODE_BLE);
+    esp_bt_controller_config_t bt_cfg = BT_CONTROLLER_INIT_CONFIG_DEFAULT();
+	
+    if ((err = esp_bt_controller_init(&bt_cfg)) != ESP_OK) {
+        ESP_LOGE(TAG, "%s initialize controller failed: %s\n", __func__, esp_err_to_name(err));
+        goto exit;
+    }
+
+    if ((err = esp_bt_controller_enable(ESP_BT_MODE_CLASSIC_BT)) != ESP_OK) {
+        ESP_LOGE(TAG, "%s enable controller failed: %s\n", __func__, esp_err_to_name(err));
+		goto exit;
+    }
+
+    if ((err = esp_bluedroid_init()) != ESP_OK) {
+        ESP_LOGE(TAG, "%s initialize bluedroid failed: %s\n", __func__, esp_err_to_name(err));
+		goto exit;
+    }
+
+    if ((err = esp_bluedroid_enable()) != ESP_OK) {
+        ESP_LOGE(TAG, "%s enable bluedroid failed: %s\n", __func__, esp_err_to_name(err));
+		goto exit;
+    }
+	
+	/* Bluetooth device name, connection mode and profile set up */
+	bt_app_work_dispatch((bt_av_hdl_stack_evt_t*) arg, BT_APP_EVT_STACK_UP, NULL, 0, NULL);
+	
+#if (CONFIG_BT_SSP_ENABLED)
+    /* Set default parameters for Secure Simple Pairing */
+    esp_bt_sp_param_t param_type = ESP_BT_SP_IOCAP_MODE;
+    esp_bt_io_cap_t iocap = ESP_BT_IO_CAP_IO;
+    esp_bt_gap_set_security_param(param_type, &iocap, sizeof(uint8_t));
+#endif
+	
+	running = true;
+	
+	while (running) {
+        if (pdTRUE == xQueueReceive(s_bt_app_task_queue, &msg, (portTickType)portMAX_DELAY)) {
+        	ESP_LOGV(TAG,"%s, sig 0x%x, 0x%x", __func__, msg.sig, msg.event);
+			
+            switch (msg.sig) {
+            case BT_APP_SIG_WORK_DISPATCH:
+                bt_app_work_dispatched(&msg);
+                break;
+            default:
+                ESP_LOGW(TAG,"%s, unhandled sig: %d", __func__, msg.sig);
+                break;
+            }
+
+            if (msg.param) {
+                free(msg.param);
+            }
+        } else {
+        	ESP_LOGW(TAG,"No messaged received from queue.");
+        }
+    }
+	
+	ESP_LOGD(TAG, "bt_app_task shutting down");
+	
+	if (esp_bluedroid_disable() != ESP_OK) goto exit;
+	// this disable has a sleep timer BTA_DISABLE_DELAY in bt_target.h and 
+	// if we don't wait for it then disable crashes... don't know why
+	vTaskDelay(2*200 / portTICK_PERIOD_MS);	
+	
+    ESP_LOGD(TAG, "esp_bluedroid_disable called successfully");
+    if (esp_bluedroid_deinit() != ESP_OK) goto exit;
+	
+    ESP_LOGD(TAG, "esp_bluedroid_deinit called successfully");
+    if (esp_bt_controller_disable() != ESP_OK) goto exit;
+	
+    ESP_LOGD(TAG, "esp_bt_controller_disable called successfully");
+    if (esp_bt_controller_deinit() != ESP_OK) goto exit;
+	
+	ESP_LOGD(TAG, "bt stopped successfully");	
+
+exit:
+	vQueueDelete(s_bt_app_task_queue);
+	running = false;		
+    vTaskDelete(NULL);
+}
+
+void bt_app_task_start_up(bt_av_hdl_stack_evt_t* handler)
+{
+    xTaskCreate(bt_app_task_handler, "BtAppT", 4096, handler, configMAX_PRIORITIES - 3, NULL);
+}
+
+void bt_app_task_shut_down(void)
+{
+	running = false;
+}

+ 1064 - 0
components/driver_bt/bt_app_source - Copy.c.old

@@ -0,0 +1,1064 @@
+#include <stdio.h>
+#include <string.h>
+#include <ctype.h>
+#include <stdlib.h>
+#include "bt_app_core.h"
+#include "esp_log.h"
+#include "esp_bt.h"
+#include "esp_bt_device.h"
+#include "esp_bt_main.h"
+#include "esp_gap_bt_api.h"
+#include "esp_a2dp_api.h"
+#include "esp_avrc_api.h"
+#include "esp_console.h"
+#include "esp_pthread.h"
+#include "esp_system.h"
+#include "esp_wifi.h"
+#include "freertos/timers.h"
+#include "argtable3/argtable3.h"
+#include "platform_config.h"
+#include "messaging.h"
+#include "cJSON.h"
+#include "tools.h"
+
+static const char * TAG = "bt_app_source";
+static const char * BT_RC_CT_TAG="RCCT";
+extern int32_t 	output_bt_data(uint8_t *data, int32_t len);
+extern void 	output_bt_tick(void);
+extern char*	output_state_str(void);
+extern bool		output_stopped(void);
+extern bool is_recovery_running;
+
+static void bt_app_av_state_connecting(uint16_t event, void *param);
+static void filter_inquiry_scan_result(esp_bt_gap_cb_param_t *param);
+
+char * APP_AV_STATE_DESC[] = {
+	    "APP_AV_STATE_IDLE",
+	    "APP_AV_STATE_DISCOVERING",
+	    "APP_AV_STATE_DISCOVERED",
+	    "APP_AV_STATE_UNCONNECTED",
+	    "APP_AV_STATE_CONNECTING",
+	    "APP_AV_STATE_CONNECTED",
+	    "APP_AV_STATE_DISCONNECTING"
+};
+static char *  ESP_AVRC_CT_DESC[]={
+  "ESP_AVRC_CT_CONNECTION_STATE_EVT",
+  "ESP_AVRC_CT_PASSTHROUGH_RSP_EVT",
+  "ESP_AVRC_CT_METADATA_RSP_EVT",
+  "ESP_AVRC_CT_PLAY_STATUS_RSP_EVT",
+  "ESP_AVRC_CT_CHANGE_NOTIFY_EVT",
+  "ESP_AVRC_CT_REMOTE_FEATURES_EVT",
+  "ESP_AVRC_CT_GET_RN_CAPABILITIES_RSP_EVT",
+  "ESP_AVRC_CT_SET_ABSOLUTE_VOLUME_RSP_EVT" 
+  };
+
+#define BT_APP_HEART_BEAT_EVT                (0xff00)
+// AVRCP used transaction label
+#define APP_RC_CT_TL_GET_CAPS            (0)
+#define APP_RC_CT_TL_RN_VOLUME_CHANGE    (1)
+#define PEERS_LIST_MAINTAIN_RESET -129
+#define PEERS_LIST_MAINTAIN_PURGE -129
+
+/// handler for bluetooth stack enabled events
+static void bt_av_hdl_stack_evt(uint16_t event, void *p_param);
+
+/// callback function for A2DP source
+static void bt_app_a2d_cb(esp_a2d_cb_event_t event, esp_a2d_cb_param_t *param);
+
+/// callback function for AVRCP controller
+static void bt_app_rc_ct_cb(esp_avrc_ct_cb_event_t event, esp_avrc_ct_cb_param_t *param);
+
+/// avrc CT event handler
+static void bt_av_hdl_avrc_ct_evt(uint16_t event, void *p_param);
+
+/// callback function for A2DP source audio data stream
+static void a2d_app_heart_beat(void *arg);
+
+/// A2DP application state machine
+static void bt_app_av_sm_hdlr(uint16_t event, void *param);
+
+/* A2DP application state machine handler for each state */
+static void bt_app_av_state_unconnected(uint16_t event, void *param);
+static void bt_app_av_state_connecting(uint16_t event, void *param);
+static void bt_app_av_state_connected(uint16_t event, void *param);
+static void bt_app_av_state_disconnecting(uint16_t event, void *param);
+static void handle_connect_state_unconnected(uint16_t event, esp_a2d_cb_param_t *param);
+static void handle_connect_state_connecting(uint16_t event, esp_a2d_cb_param_t *param);
+static void handle_connect_state_connected(uint16_t event, esp_a2d_cb_param_t *param);
+static void handle_connect_state_disconnecting(uint16_t event, esp_a2d_cb_param_t *param);
+static void bt_av_notify_evt_handler(uint8_t event_id, esp_avrc_rn_param_t *event_parameter);
+
+static esp_bd_addr_t s_peer_bda = {0};
+static uint8_t s_peer_bdname[ESP_BT_GAP_MAX_BDNAME_LEN + 1];
+int bt_app_source_a2d_state = APP_AV_STATE_IDLE;
+int bt_app_source_media_state = APP_AV_MEDIA_STATE_IDLE;
+static uint32_t s_pkt_cnt = 0;
+static TimerHandle_t s_tmr=NULL;
+static int prev_duration=10000;
+static esp_avrc_rn_evt_cap_mask_t s_avrc_peer_rn_cap;
+static int s_connecting_intv = 0;
+cJSON * peers_list=NULL;
+
+static struct {
+	char * sink_name;
+} squeezelite_conf;	
+
+static cJSON * peers_list_get_entry(const char * s_peer_bdname){
+    cJSON * element=NULL;
+    cJSON_ArrayForEach(element,peers_list){
+        cJSON * name = cJSON_GetObjectItem(element,"name");
+        if(name && !strcmp(cJSON_GetStringValue(name),s_peer_bdname)){
+            ESP_LOGV(TAG,"Entry name %s found in current scan list", s_peer_bdname);
+            return element;
+        }
+    }
+    ESP_LOGV(TAG,"Entry name %s NOT found in current scan list", s_peer_bdname);
+    return NULL;
+}
+
+static void peers_list_reset(){
+    cJSON * element=NULL;
+    cJSON_ArrayForEach(element,peers_list){
+        cJSON * rssi = cJSON_GetObjectItem(element,"rssi");
+        if(rssi){
+            rssi->valuedouble = -129;
+            rssi->valueint = -129;
+        }
+    }
+}
+
+static void peers_list_purge(){
+    cJSON * element=NULL;
+    cJSON_ArrayForEach(element,peers_list){
+        cJSON * rssi_val = cJSON_GetObjectItem(element,"rssi");
+        if(rssi_val && rssi_val->valuedouble == -129){
+            cJSON * name = cJSON_GetObjectItem(element,"name");
+            ESP_LOGV(TAG,"Purging %s", cJSON_GetStringValue(name)?cJSON_GetStringValue(name):"Unknown");
+            cJSON_DetachItemViaPointer(peers_list,element);
+            cJSON_Delete(element);
+        }
+    }    
+}
+
+static cJSON * peers_list_create_entry(const char * s_peer_bdname, int32_t rssi){
+    cJSON * entry = cJSON_CreateObject();
+    cJSON_AddStringToObject(entry,"name",s_peer_bdname);
+    cJSON_AddNumberToObject(entry,"rssi",rssi);
+    return entry;
+}
+
+static void peers_list_update_add(const char * s_peer_bdname, int32_t rssi){
+    cJSON * element= peers_list_get_entry(s_peer_bdname);
+    if(element){
+        cJSON * rssi_val = cJSON_GetObjectItem(element,"rssi");
+        if(rssi_val && rssi_val->valuedouble != rssi){
+            ESP_LOGV(TAG,"Updating BT Sink Device: %s rssi to %i", s_peer_bdname,rssi);
+            rssi_val->valuedouble = rssi;
+            rssi_val->valueint = rssi;
+        }
+    }
+    else {
+        ESP_LOGI(TAG,"Found BT Sink Device: %s rssi is %i", s_peer_bdname,rssi);
+        element = peers_list_create_entry( s_peer_bdname,  rssi);
+        cJSON_AddItemToArray(peers_list,element);
+    }
+}
+
+static void peers_list_maintain(const char * s_peer_bdname, int32_t rssi){
+    if(!peers_list){
+        ESP_LOGV(TAG,"Initializing BT peers list");
+        peers_list=cJSON_CreateArray();
+    }
+    if(rssi==PEERS_LIST_MAINTAIN_RESET){
+        ESP_LOGV(TAG,"Resetting BT peers list");
+        peers_list_reset();
+    }
+    else if(rssi==PEERS_LIST_MAINTAIN_PURGE){
+        ESP_LOGV(TAG,"Purging BT peers list");
+        peers_list_purge();
+    }
+    if(s_peer_bdname) {
+        ESP_LOGV(TAG,"Adding/Updating peer %s rssi %i", s_peer_bdname,rssi);
+        peers_list_update_add(s_peer_bdname, rssi);
+    }
+    char * list_json = cJSON_Print(peers_list);
+    if(list_json){
+        messaging_post_message(MESSAGING_INFO, MESSAGING_CLASS_BT, list_json);
+        ESP_LOGV(TAG,"%s", list_json);
+        free(list_json);
+    }    
+}
+
+int bt_app_source_get_a2d_state(){
+    if(!is_recovery_running){
+        // if we are in recovery mode, don't log BT status
+        ESP_LOGD(TAG,"a2dp status: %u = %s", bt_app_source_a2d_state, APP_AV_STATE_DESC[bt_app_source_a2d_state]);
+    }
+    return bt_app_source_a2d_state;
+}
+
+int bt_app_source_get_media_state(){
+    ESP_LOGD(TAG,"media state : %u ", bt_app_source_media_state);
+    return bt_app_source_media_state;
+}
+
+void set_app_source_state(int new_state){
+    if(bt_app_source_a2d_state!=new_state){
+        ESP_LOGD(TAG, "Updating state from %s to %s", APP_AV_STATE_DESC[bt_app_source_a2d_state], APP_AV_STATE_DESC[new_state]);
+        bt_app_source_a2d_state=new_state;
+    }
+}
+
+void set_a2dp_media_state(int new_state){
+    if(bt_app_source_media_state!=new_state){
+        bt_app_source_media_state=new_state;
+    }
+}
+
+void hal_bluetooth_init(const char * options)
+{
+	struct {
+		struct arg_str *sink_name;
+		struct arg_end *end;
+	} squeezelite_args;
+	
+	ESP_LOGD(TAG,"Initializing Bluetooth HAL");
+
+	squeezelite_args.sink_name = arg_str0("n", "name", "<sink name>", "the name of the bluetooth to connect to");
+	squeezelite_args.end = arg_end(2);
+
+	ESP_LOGD(TAG,"Copying parameters");
+	char * opts = strdup_psram(options);
+	char **argv = malloc_init_external(sizeof(char**)*15);
+
+	size_t argv_size=15;
+
+	// change parms so ' appear as " for parsing the options
+	for (char* p = opts; (p = strchr(p, '\'')); ++p) *p = '"';
+	ESP_LOGD(TAG,"Splitting arg line: %s", opts);
+
+	argv_size = esp_console_split_argv(opts, argv, argv_size);
+	ESP_LOGD(TAG,"Parsing parameters");
+	int nerrors = arg_parse(argv_size , argv, (void **) &squeezelite_args);
+	if (nerrors != 0) {
+		ESP_LOGD(TAG,"Parsing Errors");
+		arg_print_errors(stdout, squeezelite_args.end, "BT");
+		arg_print_glossary_gnu(stdout, (void **) &squeezelite_args);
+		free(opts);
+		free(argv);
+		return;
+	}
+
+    if(squeezelite_args.sink_name->count == 0)
+    {
+        squeezelite_conf.sink_name = config_alloc_get_default(NVS_TYPE_STR, "a2dp_sink_name", NULL, 0);
+        if(!squeezelite_conf.sink_name  || strlen(squeezelite_conf.sink_name)==0 ){
+            ESP_LOGW(TAG,"Unable to retrieve the a2dp sink name from nvs.");
+        }
+    } else {
+        squeezelite_conf.sink_name=strdup_psram(squeezelite_args.sink_name->sval[0]);
+        // sync with NVS
+        esp_err_t err=ESP_OK;
+        if((err= config_set_value(NVS_TYPE_STR, "a2dp_sink_name", squeezelite_args.sink_name->sval[0]))!=ESP_OK){
+            ESP_LOGE(TAG,"Error setting Bluetooth audio device name %s. %s",squeezelite_args.sink_name->sval[0], esp_err_to_name(err));
+        }
+        else {
+            ESP_LOGI(TAG,"Bluetooth audio device name changed to %s",squeezelite_args.sink_name->sval[0]);
+        }                
+    }
+
+	ESP_LOGD(TAG,"Freeing options");
+	free(argv);
+	free(opts);
+	
+	// create task and run event loop
+    bt_app_task_start_up(bt_av_hdl_stack_evt);
+
+	/*
+	 * Set default parameters for Legacy Pairing
+	 * Use variable pin, input pin code when pairing
+	*/
+	esp_bt_pin_type_t pin_type = ESP_BT_PIN_TYPE_VARIABLE;
+	esp_bt_pin_code_t pin_code;
+	esp_bt_gap_set_pin(pin_type, 0, pin_code);
+
+}
+
+void hal_bluetooth_stop(void) {
+	bt_app_task_shut_down();
+}	
+
+static void bt_app_a2d_cb(esp_a2d_cb_event_t event, esp_a2d_cb_param_t *param)
+{
+    bt_app_work_dispatch(bt_app_av_sm_hdlr, event, param, sizeof(esp_a2d_cb_param_t), NULL);
+}
+
+static void handle_bt_gap_pin_req(esp_bt_gap_cb_event_t event, esp_bt_gap_cb_param_t *param){
+    char * pin_str = config_alloc_get_default(NVS_TYPE_STR, "a2dp_spin", "0000", 0);
+    int pinlen=pin_str?strlen(pin_str):0;
+    if (pin_str && ((!param->pin_req.min_16_digit && pinlen==4) || (param->pin_req.min_16_digit && pinlen==16)))  {
+        ESP_LOGI(TAG,"Input pin code %s: ",pin_str);
+        esp_bt_pin_code_t pin_code;
+        for (size_t i = 0; i < pinlen; i++)
+        {
+            pin_code[i] = pin_str[i];
+        }
+        esp_bt_gap_pin_reply(param->pin_req.bda, true, pinlen, pin_code);
+    }
+    else {
+        if(pinlen>0){
+            ESP_LOGW(TAG,"Pin length: %u does not match the length expected by the device: %u", pinlen, ((param->pin_req.min_16_digit)?16:4));
+        }
+        else {
+            ESP_LOGW(TAG, "No security Pin provided. Trying with default pins.");
+        }
+        if (param->pin_req.min_16_digit) {
+            ESP_LOGI(TAG,"Input pin code: 0000 0000 0000 0000");
+            esp_bt_pin_code_t pin_code = {0};
+            esp_bt_gap_pin_reply(param->pin_req.bda, true, 16, pin_code);
+        } else {
+            ESP_LOGI(TAG,"Input pin code: 1234");
+            esp_bt_pin_code_t pin_code;
+            pin_code[0] = '1';
+            pin_code[1] = '2';
+            pin_code[2] = '3';
+            pin_code[3] = '4';
+            esp_bt_gap_pin_reply(param->pin_req.bda, true, 4, pin_code);
+        }            
+    }
+    FREE_AND_NULL(pin_str);
+}
+
+static void bt_app_gap_cb(esp_bt_gap_cb_event_t event, esp_bt_gap_cb_param_t *param)
+{
+
+    switch (event) {
+    case ESP_BT_GAP_DISC_RES_EVT: {
+        filter_inquiry_scan_result(param);
+        break;
+    }
+    case ESP_BT_GAP_DISC_STATE_CHANGED_EVT: {
+		
+		if (param->disc_st_chg.state == ESP_BT_GAP_DISCOVERY_STOPPED) {
+            peers_list_maintain(NULL, PEERS_LIST_MAINTAIN_PURGE);
+            if (bt_app_source_a2d_state == APP_AV_STATE_DISCOVERED) {
+				set_app_source_state(APP_AV_STATE_CONNECTING);
+				ESP_LOGI(TAG,"Discovery completed.  Ready to start connecting to %s. ", s_peer_bdname);
+                esp_a2d_source_connect(s_peer_bda);
+            } else {
+                // not discovered, continue to discover
+                ESP_LOGI(TAG, "Device discovery failed, continue to discover...");
+                esp_bt_gap_start_discovery(ESP_BT_INQ_MODE_GENERAL_INQUIRY, 10, 0);
+            }
+        } else if (param->disc_st_chg.state == ESP_BT_GAP_DISCOVERY_STARTED) {
+            ESP_LOGI(TAG, "Discovery started.");
+			peers_list_maintain(NULL, PEERS_LIST_MAINTAIN_RESET);
+        }
+        break;
+    }
+    case ESP_BT_GAP_RMT_SRVCS_EVT:
+    	ESP_LOG_DEBUG_EVENT(TAG,QUOTE(ESP_BT_GAP_RMT_SRVCS_EVT));
+    	break;
+    case ESP_BT_GAP_RMT_SRVC_REC_EVT:
+    	ESP_LOG_DEBUG_EVENT(TAG,QUOTE(ESP_BT_GAP_RMT_SRVC_REC_EVT));
+        break;
+    case ESP_BT_GAP_AUTH_CMPL_EVT: {
+    	if (param->auth_cmpl.stat == ESP_BT_STATUS_SUCCESS) {
+            ESP_LOGI(TAG,"authentication success: %s", param->auth_cmpl.device_name);
+            //esp_log_buffer_hex(param->auth_cmpl.bda, ESP_BD_ADDR_LEN);
+        } else {
+            ESP_LOGE(TAG,"authentication failed, status:%d", param->auth_cmpl.stat);
+        }
+        break;
+    }
+    case ESP_BT_GAP_PIN_REQ_EVT: 
+        handle_bt_gap_pin_req(event, param);
+        break;
+
+#if (CONFIG_BT_SSP_ENABLED == true)
+    case ESP_BT_GAP_CFM_REQ_EVT:
+        ESP_LOGI(TAG,"ESP_BT_GAP_CFM_REQ_EVT Please compare the numeric value: %d", param->cfm_req.num_val);
+        esp_bt_gap_ssp_confirm_reply(param->cfm_req.bda, true);
+        break;
+    case ESP_BT_GAP_KEY_NOTIF_EVT:
+        ESP_LOGI(TAG,"ESP_BT_GAP_KEY_NOTIF_EVT passkey:%d", param->key_notif.passkey);
+        break;
+        ESP_LOGI(TAG,"ESP_BT_GAP_KEY_REQ_EVT Please enter passkey!");
+        break;
+#endif
+
+    default: {
+        ESP_LOGI(TAG,"event: %d", event);
+        break;
+    }
+    }
+    return;
+}
+int heart_beat_delay[] = {
+    1000,
+    1000,
+    1000,
+    1000,
+    10000,
+    500,
+    1000
+};
+
+static void a2d_app_heart_beat(void *arg)
+{
+    bt_app_work_dispatch(bt_app_av_sm_hdlr, BT_APP_HEART_BEAT_EVT, NULL, 0, NULL);
+    int tmrduration=heart_beat_delay[bt_app_source_a2d_state];
+    if(prev_duration!=tmrduration){
+        xTimerChangePeriod(s_tmr,tmrduration, portMAX_DELAY);
+        ESP_LOGD(TAG,"New heartbeat is %u",tmrduration);
+        prev_duration=tmrduration;
+    }
+    else {
+        ESP_LOGD(TAG,"Starting Heart beat timer for %ums",tmrduration);
+    }
+    xTimerStart(s_tmr, portMAX_DELAY);
+}
+
+static const char * conn_state_str(esp_a2d_connection_state_t state){
+    char * statestr = "Unknown";
+     switch (state)
+        {
+        case ESP_A2D_CONNECTION_STATE_DISCONNECTED:
+            statestr=STR(ESP_A2D_CONNECTION_STATE_DISCONNECTED);
+            break;
+        case ESP_A2D_CONNECTION_STATE_CONNECTING:
+            statestr=STR(ESP_A2D_CONNECTION_STATE_CONNECTING);
+            break;
+        case ESP_A2D_CONNECTION_STATE_CONNECTED:
+            statestr=STR(ESP_A2D_CONNECTION_STATE_CONNECTED);
+            break;
+        case ESP_A2D_CONNECTION_STATE_DISCONNECTING:
+            statestr=STR(ESP_A2D_CONNECTION_STATE_DISCONNECTING);
+            break;
+        default:
+            break;
+        }
+    return statestr;
+}
+
+static void unexpected_connection_state(int from, esp_a2d_connection_state_t to)
+{
+    ESP_LOGW(TAG,"Unexpected connection state change. App State: %s (%u) Connection State %s (%u)", APP_AV_STATE_DESC[from], from,conn_state_str(to), to);
+}
+
+static void handle_connect_state_unconnected(uint16_t event, esp_a2d_cb_param_t *param){
+    ESP_LOGV(TAG, "A2DP Event while unconnected ");
+    switch (param->conn_stat.state)
+    {
+        case ESP_A2D_CONNECTION_STATE_DISCONNECTED:
+            unexpected_connection_state(bt_app_source_a2d_state, param->conn_stat.state);
+            break;
+        case ESP_A2D_CONNECTION_STATE_CONNECTING:
+            unexpected_connection_state(bt_app_source_a2d_state, param->conn_stat.state);
+            break;
+        case ESP_A2D_CONNECTION_STATE_CONNECTED:
+            unexpected_connection_state(bt_app_source_a2d_state, param->conn_stat.state);
+            ESP_LOGE(TAG,"Connection state event received while status was unconnected.  Routing message to connecting state handler. State : %u",param->conn_stat.state);
+            if (param->conn_stat.state == ESP_A2D_CONNECTION_STATE_CONNECTED){
+                handle_connect_state_connecting(event, param);
+            }
+        break;
+        case ESP_A2D_CONNECTION_STATE_DISCONNECTING:
+            unexpected_connection_state(bt_app_source_a2d_state, param->conn_stat.state);
+            break;
+        default:
+            break;
+    }
+
+}
+
+static void handle_connect_state_connecting(uint16_t event, esp_a2d_cb_param_t *param){
+    ESP_LOGV(TAG, "A2DP connection state event : %s ",conn_state_str(param->conn_stat.state));
+
+    switch (param->conn_stat.state)
+    {
+        case ESP_A2D_CONNECTION_STATE_DISCONNECTED:
+            if(param->conn_stat.disc_rsn!=ESP_A2D_DISC_RSN_NORMAL){
+                ESP_LOGE(TAG,"A2DP had an abnormal disconnect event");
+            }
+            else {
+                ESP_LOGW(TAG,"A2DP connect unsuccessful");
+            }
+            set_app_source_state(APP_AV_STATE_UNCONNECTED);
+            break;
+        case ESP_A2D_CONNECTION_STATE_CONNECTING:
+            break;
+        case ESP_A2D_CONNECTION_STATE_CONNECTED:
+            set_app_source_state(APP_AV_STATE_CONNECTED);
+            set_a2dp_media_state(APP_AV_MEDIA_STATE_IDLE);
+            ESP_LOGD(TAG,"Setting scan mode to ESP_BT_NON_CONNECTABLE, ESP_BT_NON_DISCOVERABLE");
+            esp_bt_gap_set_scan_mode(ESP_BT_NON_CONNECTABLE, ESP_BT_NON_DISCOVERABLE);
+            ESP_LOGD(TAG,"Done setting scan mode. App state is now CONNECTED and media state IDLE.");
+            break;
+        case ESP_A2D_CONNECTION_STATE_DISCONNECTING:
+            unexpected_connection_state(bt_app_source_a2d_state, param->conn_stat.state); 
+            set_app_source_state(APP_AV_STATE_DISCONNECTING);       
+            break;
+        default:
+            break;
+    }
+}
+static void handle_connect_state_connected(uint16_t event, esp_a2d_cb_param_t *param){
+    ESP_LOGV(TAG, "A2DP Event while connected ");
+    switch (param->conn_stat.state)
+    {
+        case ESP_A2D_CONNECTION_STATE_DISCONNECTED:
+            ESP_LOGW(TAG,"a2dp disconnected");
+            set_app_source_state(APP_AV_STATE_UNCONNECTED);
+            esp_bt_gap_set_scan_mode(ESP_BT_CONNECTABLE, ESP_BT_GENERAL_DISCOVERABLE);
+            break;
+        case ESP_A2D_CONNECTION_STATE_CONNECTING:
+            unexpected_connection_state(bt_app_source_a2d_state, param->conn_stat.state);  
+            break;
+        case ESP_A2D_CONNECTION_STATE_CONNECTED:
+            unexpected_connection_state(bt_app_source_a2d_state, param->conn_stat.state);
+            break;
+        case ESP_A2D_CONNECTION_STATE_DISCONNECTING:
+            set_app_source_state(APP_AV_STATE_DISCONNECTING);        
+
+            break;
+        default:
+            break;
+    }
+}
+
+static void handle_connect_state_disconnecting(uint16_t event, esp_a2d_cb_param_t *param){
+    ESP_LOGV(TAG, "A2DP Event while disconnecting ");
+    switch (param->conn_stat.state)
+    {
+        case ESP_A2D_CONNECTION_STATE_DISCONNECTED:
+            ESP_LOGI(TAG,"a2dp disconnected");
+            set_app_source_state(APP_AV_STATE_UNCONNECTED);
+            esp_bt_gap_set_scan_mode(ESP_BT_CONNECTABLE, ESP_BT_GENERAL_DISCOVERABLE);        
+            break;
+        case ESP_A2D_CONNECTION_STATE_CONNECTING:
+            unexpected_connection_state(bt_app_source_a2d_state, param->conn_stat.state);  
+            break;
+        case ESP_A2D_CONNECTION_STATE_CONNECTED:
+            unexpected_connection_state(bt_app_source_a2d_state, param->conn_stat.state);  
+            break;
+        case ESP_A2D_CONNECTION_STATE_DISCONNECTING:
+            unexpected_connection_state(bt_app_source_a2d_state, param->conn_stat.state);
+            break;
+        default:
+            break;
+    }
+
+}
+
+static void bt_app_av_sm_hdlr(uint16_t event, void *param)
+{
+    ESP_LOGV(TAG,"bt_app_av_sm_hdlr.%s a2d state: %s", event==BT_APP_HEART_BEAT_EVT?"Heart Beat.":"",APP_AV_STATE_DESC[bt_app_source_a2d_state]);
+    switch (bt_app_source_a2d_state) {
+    case APP_AV_STATE_DISCOVERING:
+    	ESP_LOGV(TAG,"state %s, evt 0x%x, output state: %s", APP_AV_STATE_DESC[bt_app_source_a2d_state], event, output_state_str());
+    	break;
+    case APP_AV_STATE_DISCOVERED:
+    	ESP_LOGV(TAG,"state %s, evt 0x%x, output state: %s", APP_AV_STATE_DESC[bt_app_source_a2d_state], event, output_state_str());
+        break;
+    case APP_AV_STATE_UNCONNECTED:
+        bt_app_av_state_unconnected(event, param);
+        break;
+    case APP_AV_STATE_CONNECTING:
+        bt_app_av_state_connecting(event, param);
+        break;
+    case APP_AV_STATE_CONNECTED:
+        bt_app_av_state_connected(event, param);
+        break;
+    case APP_AV_STATE_DISCONNECTING:
+        bt_app_av_state_disconnecting(event, param);
+        break;
+    default:
+        ESP_LOGE(TAG,"%s invalid state %d", __func__, bt_app_source_a2d_state);
+        break;
+    }
+}
+
+static char *bda2str(esp_bd_addr_t bda, char *str, size_t size)
+{
+    if (bda == NULL || str == NULL || size < 18) {
+        return NULL;
+    }
+
+    uint8_t *p = bda;
+    sprintf(str, "%02x:%02x:%02x:%02x:%02x:%02x",
+            p[0], p[1], p[2], p[3], p[4], p[5]);
+    return str;
+}
+static bool get_name_from_eir(uint8_t *eir, uint8_t *bdname, uint8_t *bdname_len)
+{
+    uint8_t *rmt_bdname = NULL;
+    uint8_t rmt_bdname_len = 0;
+
+    if (!eir) {
+        return false;
+    }
+
+    rmt_bdname = esp_bt_gap_resolve_eir_data(eir, ESP_BT_EIR_TYPE_CMPL_LOCAL_NAME, &rmt_bdname_len);
+    if (!rmt_bdname) {
+        rmt_bdname = esp_bt_gap_resolve_eir_data(eir, ESP_BT_EIR_TYPE_SHORT_LOCAL_NAME, &rmt_bdname_len);
+    }
+
+    if (rmt_bdname) {
+        if (rmt_bdname_len > ESP_BT_GAP_MAX_BDNAME_LEN) {
+            rmt_bdname_len = ESP_BT_GAP_MAX_BDNAME_LEN;
+        }
+
+        if (bdname) {
+            memcpy(bdname, rmt_bdname, rmt_bdname_len);
+            bdname[rmt_bdname_len] = '\0';
+        }
+        if (bdname_len) {
+            *bdname_len = rmt_bdname_len;
+        }
+        return true;
+    }
+
+    return false;
+}
+
+static void filter_inquiry_scan_result(esp_bt_gap_cb_param_t *param)
+{
+    char bda_str[18];
+    uint32_t cod = 0;
+    int32_t rssi = -129; /* invalid value */
+    uint8_t *eir = NULL;
+    uint8_t nameLen = 0;
+    esp_bt_gap_dev_prop_t *p;
+    memset(bda_str, 0x00, sizeof(bda_str));
+    if(bt_app_source_a2d_state != APP_AV_STATE_DISCOVERING)
+    {
+    	// Ignore messages that might have been queued already
+    	// when we've discovered the target device.
+    	return;
+    }
+    memset(s_peer_bdname, 0x00,sizeof(s_peer_bdname));
+
+    bda2str(param->disc_res.bda, bda_str, 18);
+
+    ESP_LOGV(TAG,"\n=======================\nScanned device: %s",bda_str );
+    for (int i = 0; i < param->disc_res.num_prop; i++) {
+        p = param->disc_res.prop + i;
+        switch (p->type) {
+        case ESP_BT_GAP_DEV_PROP_COD:
+            cod = *(uint32_t *)(p->val);
+            ESP_LOGV(TAG,"-- Class of Device: 0x%x", cod);
+            break;
+        case ESP_BT_GAP_DEV_PROP_RSSI:
+            rssi = *(int8_t *)(p->val);
+            ESP_LOGV(TAG,"-- RSSI: %d", rssi);
+            break;
+        case ESP_BT_GAP_DEV_PROP_EIR:
+            eir = (uint8_t *)(p->val);
+            ESP_LOGV(TAG,"-- EIR: %u", *eir);
+            break;
+        case ESP_BT_GAP_DEV_PROP_BDNAME:
+            nameLen = (p->len > ESP_BT_GAP_MAX_BDNAME_LEN) ? ESP_BT_GAP_MAX_BDNAME_LEN : (uint8_t)p->len;
+            memcpy(s_peer_bdname, (uint8_t *)(p->val), nameLen);
+            s_peer_bdname[nameLen] = '\0';
+            ESP_LOGV(TAG,"-- Name: %s", s_peer_bdname);
+            break;
+        default:
+            break;
+        }
+    }
+    if (!esp_bt_gap_is_valid_cod(cod)){
+    /* search for device with MAJOR service class as "rendering" in COD */
+    	ESP_LOGV(TAG,"--Invalid class of device. Skipping.\n");
+    	return;
+    }
+    else if (!(esp_bt_gap_get_cod_srvc(cod) & ESP_BT_COD_SRVC_RENDERING))
+    {
+    	ESP_LOGV(TAG,"--Not a rendering device. Skipping.\n");
+    	return;
+    }
+
+    if (eir) {
+    	ESP_LOGV(TAG,"--Getting details from eir.\n");
+        get_name_from_eir(eir, s_peer_bdname, NULL);
+        ESP_LOGV(TAG,"--Device name is %s\n",s_peer_bdname);
+    }
+    if(strlen((char *)s_peer_bdname)>0) {
+        peers_list_maintain((const char *)s_peer_bdname, rssi);    
+    }
+
+    if (squeezelite_conf.sink_name && strlen(squeezelite_conf.sink_name) >0 && strcmp((char *)s_peer_bdname, squeezelite_conf.sink_name) == 0) {
+        ESP_LOGI(TAG,"Found our target device. address %s, name %s", bda_str, s_peer_bdname);
+		memcpy(s_peer_bda, param->disc_res.bda, ESP_BD_ADDR_LEN);
+        set_app_source_state(APP_AV_STATE_DISCOVERED);
+        esp_bt_gap_cancel_discovery();
+    } else {
+    	ESP_LOGV(TAG,"Not the device we are looking for (%s). Continuing scan", squeezelite_conf.sink_name?squeezelite_conf.sink_name:"N/A");
+    }
+}
+
+static void bt_av_hdl_stack_evt(uint16_t event, void *p_param)
+{
+    switch (event) {
+    case BT_APP_EVT_STACK_UP: {
+    	ESP_LOGI(TAG,"BT Stack going up.");
+        /* set up device name */
+
+
+        char * a2dp_dev_name = 	config_alloc_get_default(NVS_TYPE_STR, "a2dp_dev_name", CONFIG_A2DP_DEV_NAME, 0);
+    	if(a2dp_dev_name  == NULL){
+    		ESP_LOGW(TAG,"Unable to retrieve the a2dp device name from nvs");
+    		esp_bt_dev_set_device_name(CONFIG_A2DP_DEV_NAME);
+    	}
+    	else {
+    		esp_bt_dev_set_device_name(a2dp_dev_name);
+    		free(a2dp_dev_name);
+    	}
+
+        ESP_LOGI(TAG,"Preparing to connect");
+
+        /* register GAP callback function */
+        esp_bt_gap_register_callback(bt_app_gap_cb);
+
+        /* initialize AVRCP controller */
+        esp_avrc_ct_init();
+        esp_avrc_ct_register_callback(bt_app_rc_ct_cb);
+
+        esp_avrc_rn_evt_cap_mask_t evt_set = {0};
+        esp_avrc_rn_evt_bit_mask_operation(ESP_AVRC_BIT_MASK_OP_SET, &evt_set, ESP_AVRC_RN_VOLUME_CHANGE);
+        assert(esp_avrc_tg_set_rn_evt_cap(&evt_set) == ESP_OK);
+
+
+        /* initialize A2DP source */
+        esp_a2d_register_callback(&bt_app_a2d_cb);
+        esp_a2d_source_register_data_callback(&output_bt_data);
+        esp_a2d_source_init();
+
+        /* set discoverable and connectable mode */
+        esp_bt_gap_set_scan_mode(ESP_BT_CONNECTABLE, ESP_BT_GENERAL_DISCOVERABLE);
+
+        /* start device discovery */
+        ESP_LOGI(TAG,"Starting device discovery...");
+        set_app_source_state(APP_AV_STATE_DISCOVERING);
+        esp_bt_gap_start_discovery(ESP_BT_INQ_MODE_GENERAL_INQUIRY, 10, 0);
+
+        /* create and start heart beat timer */
+        int tmr_id = 0;
+        s_tmr = xTimerCreate("connTmr", ( prev_duration/ portTICK_RATE_MS),pdFALSE, (void *)tmr_id, a2d_app_heart_beat);        
+        xTimerStart(s_tmr, portMAX_DELAY);
+        break;
+    }
+    default:
+    	ESP_LOGE(TAG,"%s unhandled evt %d", __func__, event);
+        break;
+    }
+}
+static void bt_app_rc_ct_cb(esp_avrc_ct_cb_event_t event, esp_avrc_ct_cb_param_t *param)
+{
+    switch (event) {
+    case ESP_AVRC_CT_METADATA_RSP_EVT:
+    case ESP_AVRC_CT_CONNECTION_STATE_EVT:
+    case ESP_AVRC_CT_PASSTHROUGH_RSP_EVT:
+    case ESP_AVRC_CT_CHANGE_NOTIFY_EVT:
+    case ESP_AVRC_CT_REMOTE_FEATURES_EVT:
+    case ESP_AVRC_CT_GET_RN_CAPABILITIES_RSP_EVT:
+    case ESP_AVRC_CT_SET_ABSOLUTE_VOLUME_RSP_EVT: {
+        ESP_LOGD(TAG,"Received %s message", ESP_AVRC_CT_DESC[event]);
+        bt_app_work_dispatch(bt_av_hdl_avrc_ct_evt, event, param, sizeof(esp_avrc_ct_cb_param_t), NULL);
+        break;
+    }
+    default:
+        ESP_LOGE(BT_RC_CT_TAG, "Invalid AVRC event: %d", event);
+        break;
+    }
+}
+static void bt_app_av_media_proc(uint16_t event, void *param)
+{
+    esp_a2d_cb_param_t *a2d = NULL;
+    switch (bt_app_source_media_state) {
+    case APP_AV_MEDIA_STATE_IDLE: {
+    	if (event == BT_APP_HEART_BEAT_EVT) {
+            if(!output_stopped())
+            {
+            	ESP_LOGI(TAG,"Output state is %s, Checking if A2DP is ready.", output_state_str());
+            	esp_a2d_media_ctrl(ESP_A2D_MEDIA_CTRL_CHECK_SRC_RDY);
+            }
+
+        } else if (event == ESP_A2D_MEDIA_CTRL_ACK_EVT) {
+        	a2d = (esp_a2d_cb_param_t *)(param);
+			if (a2d->media_ctrl_stat.cmd == ESP_A2D_MEDIA_CTRL_CHECK_SRC_RDY &&
+					a2d->media_ctrl_stat.status == ESP_A2D_MEDIA_CTRL_ACK_SUCCESS
+					) {
+				ESP_LOGI(TAG,"a2dp media ready, starting playback!");
+				set_a2dp_media_state(APP_AV_MEDIA_STATE_STARTING);
+				esp_a2d_media_ctrl(ESP_A2D_MEDIA_CTRL_START);
+			}
+        }
+        break;
+    }
+
+    case APP_AV_MEDIA_STATE_STARTING: {
+    	if (event == ESP_A2D_MEDIA_CTRL_ACK_EVT) {
+            a2d = (esp_a2d_cb_param_t *)(param);
+            if (a2d->media_ctrl_stat.cmd == ESP_A2D_MEDIA_CTRL_START &&
+                    a2d->media_ctrl_stat.status == ESP_A2D_MEDIA_CTRL_ACK_SUCCESS) {
+            	ESP_LOGI(TAG,"a2dp media started successfully.");
+                set_a2dp_media_state(APP_AV_MEDIA_STATE_STARTED);
+            } else {
+                // not started succesfully, transfer to idle state
+            	ESP_LOGI(TAG,"a2dp media start failed.");
+                set_a2dp_media_state(APP_AV_MEDIA_STATE_IDLE);
+            }
+        }
+        break;
+    }
+    case APP_AV_MEDIA_STATE_STARTED: {
+        if (event == BT_APP_HEART_BEAT_EVT) {
+        	if(output_stopped()) {
+        		ESP_LOGI(TAG,"Output state is %s. Stopping a2dp media ...", output_state_str());
+                set_a2dp_media_state(APP_AV_MEDIA_STATE_STOPPING);
+                esp_a2d_media_ctrl(ESP_A2D_MEDIA_CTRL_STOP);
+            } else {
+				output_bt_tick();	
+        	}
+        }
+        break;
+    }
+    case APP_AV_MEDIA_STATE_STOPPING: {
+    	ESP_LOG_DEBUG_EVENT(TAG,QUOTE(APP_AV_MEDIA_STATE_STOPPING));
+        if (event == ESP_A2D_MEDIA_CTRL_ACK_EVT) {
+            a2d = (esp_a2d_cb_param_t *)(param);
+            if (a2d->media_ctrl_stat.cmd == ESP_A2D_MEDIA_CTRL_STOP &&
+                    a2d->media_ctrl_stat.status == ESP_A2D_MEDIA_CTRL_ACK_SUCCESS) {
+                ESP_LOGI(TAG,"a2dp media stopped successfully...");
+               	set_a2dp_media_state(APP_AV_MEDIA_STATE_IDLE);
+            } else {
+                ESP_LOGI(TAG,"a2dp media stopping...");
+                esp_a2d_media_ctrl(ESP_A2D_MEDIA_CTRL_STOP);
+            }
+        }
+        break;
+    }
+
+    case APP_AV_MEDIA_STATE_WAIT_DISCONNECT:{
+    	esp_a2d_source_disconnect(s_peer_bda);
+		set_app_source_state(APP_AV_STATE_DISCONNECTING);
+		ESP_LOGI(TAG,"a2dp disconnecting...");
+    }
+    }
+}
+
+static void bt_app_av_state_unconnected(uint16_t event, void *param)
+{
+    ESP_LOGV(TAG, "Handling state unconnected A2DP event");
+	switch (event) {
+    case ESP_A2D_CONNECTION_STATE_EVT:
+        handle_connect_state_unconnected(event, (esp_a2d_cb_param_t *)param);
+    	break;
+    case ESP_A2D_AUDIO_STATE_EVT:
+    	ESP_LOG_DEBUG_EVENT(TAG,QUOTE(ESP_A2D_AUDIO_STATE_EVT));
+    	break;
+    case ESP_A2D_AUDIO_CFG_EVT:
+    	ESP_LOG_DEBUG_EVENT(TAG,QUOTE(ESP_A2D_AUDIO_CFG_EVT));
+    	break;
+    case ESP_A2D_MEDIA_CTRL_ACK_EVT:
+    	ESP_LOG_DEBUG_EVENT(TAG,QUOTE(ESP_A2D_MEDIA_CTRL_ACK_EVT));
+    	break;
+    case BT_APP_HEART_BEAT_EVT: {
+        ESP_LOG_DEBUG_EVENT(TAG,QUOTE(BT_APP_HEART_BEAT_EVT));
+        switch (esp_bluedroid_get_status()) {
+		case ESP_BLUEDROID_STATUS_UNINITIALIZED:
+			ESP_LOGV(TAG,"BlueDroid Status is ESP_BLUEDROID_STATUS_UNINITIALIZED.");
+			break;
+		case ESP_BLUEDROID_STATUS_INITIALIZED:
+			ESP_LOGV(TAG,"BlueDroid Status is ESP_BLUEDROID_STATUS_INITIALIZED.");
+			break;
+		case ESP_BLUEDROID_STATUS_ENABLED:
+			ESP_LOGV(TAG,"BlueDroid Status is ESP_BLUEDROID_STATUS_ENABLED.");
+			break;
+		default:
+			break;
+		}
+        uint8_t *p = s_peer_bda;
+        ESP_LOGI(TAG, "a2dp connecting to %s, BT peer: %02x:%02x:%02x:%02x:%02x:%02x",s_peer_bdname,p[0], p[1], p[2], p[3], p[4], p[5]);
+        if(esp_a2d_source_connect(s_peer_bda)==ESP_OK) {  
+            set_app_source_state(APP_AV_STATE_CONNECTING);
+            s_connecting_intv = 0;
+		}
+		else {
+            set_app_source_state(APP_AV_STATE_UNCONNECTED);
+			// there was an issue connecting... continue to discover
+			ESP_LOGE(TAG,"Attempt at connecting failed, restart at discover...");
+			esp_bt_gap_start_discovery(ESP_BT_INQ_MODE_GENERAL_INQUIRY, 10, 0);
+        }
+        break;
+    }
+    default:
+    	ESP_LOGE(TAG,"%s unhandled evt %d", __func__, event);
+        break;
+    }
+}
+
+static void bt_app_av_state_connecting(uint16_t event, void *param)
+{
+    switch (event) {
+    case ESP_A2D_CONNECTION_STATE_EVT:
+        handle_connect_state_connecting(event, (esp_a2d_cb_param_t *)param);
+        break;
+    case ESP_A2D_AUDIO_STATE_EVT:
+    	ESP_LOG_DEBUG_EVENT(TAG,QUOTE(ESP_A2D_AUDIO_STATE_EVT));
+    	break;
+    case ESP_A2D_AUDIO_CFG_EVT:
+    	ESP_LOG_DEBUG_EVENT(TAG,QUOTE(ESP_A2D_AUDIO_CFG_EVT));
+    	break;
+    case ESP_A2D_MEDIA_CTRL_ACK_EVT:
+    	ESP_LOG_DEBUG_EVENT(TAG,QUOTE(ESP_A2D_MEDIA_CTRL_ACK_EVT));
+    	break;
+    case BT_APP_HEART_BEAT_EVT:
+        if (++s_connecting_intv >= 2) {
+            set_app_source_state(APP_AV_STATE_UNCONNECTED);
+            ESP_LOGW(TAG,"A2DP Connect time out!  Setting state to Unconnected. ");
+            s_connecting_intv = 0;
+        }
+        break;
+    default:
+        ESP_LOGE(TAG,"%s unhandled evt %d", __func__, event);
+        break;
+    }
+}
+
+
+static void bt_app_av_state_connected(uint16_t event, void *param)
+{
+    esp_a2d_cb_param_t *a2d = NULL;
+    switch (event) {
+    case ESP_A2D_CONNECTION_STATE_EVT: {
+        handle_connect_state_connected(event, (esp_a2d_cb_param_t *)param);
+        break;
+    }
+    case ESP_A2D_AUDIO_STATE_EVT: {
+    	ESP_LOG_DEBUG_EVENT(TAG,QUOTE(ESP_A2D_AUDIO_STATE_EVT));
+        a2d = (esp_a2d_cb_param_t *)(param);
+        if (ESP_A2D_AUDIO_STATE_STARTED == a2d->audio_stat.state) {
+            s_pkt_cnt = 0;
+        }
+        break;
+    }
+    case ESP_A2D_AUDIO_CFG_EVT:
+        // not suppposed to occur for A2DP source
+    	ESP_LOG_DEBUG_EVENT(TAG,QUOTE(ESP_A2D_AUDIO_CFG_EVT));
+        break;
+    case ESP_A2D_MEDIA_CTRL_ACK_EVT:{
+    	ESP_LOG_DEBUG_EVENT(TAG,QUOTE(ESP_A2D_MEDIA_CTRL_ACK_EVT));
+            bt_app_av_media_proc(event, param);
+            break;
+        }
+    case BT_APP_HEART_BEAT_EVT: {
+    	ESP_LOGV(TAG,QUOTE(BT_APP_HEART_BEAT_EVT));
+        bt_app_av_media_proc(event, param);
+        break;
+    }
+    default:
+        ESP_LOGE(TAG,"%s unhandled evt %d", __func__, event);
+        break;
+    }
+}
+
+static void bt_app_av_state_disconnecting(uint16_t event, void *param)
+{
+    switch (event) {
+        case ESP_A2D_CONNECTION_STATE_EVT: 
+            handle_connect_state_disconnecting( event, (esp_a2d_cb_param_t *)param);
+            break;
+        case ESP_A2D_AUDIO_STATE_EVT:
+            ESP_LOG_DEBUG_EVENT(TAG,QUOTE(ESP_A2D_AUDIO_STATE_EVT));
+            break;
+        case ESP_A2D_AUDIO_CFG_EVT:
+            ESP_LOG_DEBUG_EVENT(TAG,QUOTE(ESP_A2D_AUDIO_CFG_EVT));
+            break;
+        case ESP_A2D_MEDIA_CTRL_ACK_EVT:
+            ESP_LOG_DEBUG_EVENT(TAG,QUOTE(ESP_A2D_MEDIA_CTRL_ACK_EVT));
+            break;
+        case BT_APP_HEART_BEAT_EVT:
+            ESP_LOG_DEBUG_EVENT(TAG,QUOTE(BT_APP_HEART_BEAT_EVT));
+            break;
+        default:
+            ESP_LOGE(TAG,"%s unhandled evt %d", __func__, event);
+            break;
+        }
+}
+
+static void bt_av_volume_changed(void)
+{
+    if (esp_avrc_rn_evt_bit_mask_operation(ESP_AVRC_BIT_MASK_OP_TEST, &s_avrc_peer_rn_cap,
+                                           ESP_AVRC_RN_VOLUME_CHANGE)) {
+        esp_avrc_ct_send_register_notification_cmd(APP_RC_CT_TL_RN_VOLUME_CHANGE, ESP_AVRC_RN_VOLUME_CHANGE, 0);
+    }
+}
+
+static void bt_av_notify_evt_handler(uint8_t event_id, esp_avrc_rn_param_t *event_parameter)
+{
+    switch (event_id) {
+    case ESP_AVRC_RN_VOLUME_CHANGE:
+        ESP_LOGI(BT_RC_CT_TAG, "Volume changed: %d", event_parameter->volume);
+        ESP_LOGI(BT_RC_CT_TAG, "Set absolute volume: volume %d", event_parameter->volume + 5);
+        esp_avrc_ct_send_set_absolute_volume_cmd(APP_RC_CT_TL_RN_VOLUME_CHANGE, event_parameter->volume + 5);
+        bt_av_volume_changed();
+        break;
+    }
+}
+static void bt_av_hdl_avrc_ct_evt(uint16_t event, void *p_param)
+{
+    ESP_LOGD(BT_RC_CT_TAG, "%s evt %d", __func__, event);
+    esp_avrc_ct_cb_param_t *rc = (esp_avrc_ct_cb_param_t *)(p_param);
+    switch (event) {
+    case ESP_AVRC_CT_CONNECTION_STATE_EVT: {
+        uint8_t *bda = rc->conn_stat.remote_bda;
+        ESP_LOGI(BT_RC_CT_TAG, "AVRC conn_state evt: state %d, [%02x:%02x:%02x:%02x:%02x:%02x]",
+                 rc->conn_stat.connected, bda[0], bda[1], bda[2], bda[3], bda[4], bda[5]);
+
+        if (rc->conn_stat.connected) {
+            // get remote supported event_ids of peer AVRCP Target
+            esp_avrc_ct_send_get_rn_capabilities_cmd(APP_RC_CT_TL_GET_CAPS);
+        } else {
+            // clear peer notification capability record
+            s_avrc_peer_rn_cap.bits = 0;
+        }
+        break;
+    }
+    case ESP_AVRC_CT_PASSTHROUGH_RSP_EVT: {
+        ESP_LOGI(BT_RC_CT_TAG, "AVRC passthrough rsp: key_code 0x%x, key_state %d", rc->psth_rsp.key_code, rc->psth_rsp.key_state);
+        break;
+    }
+    case ESP_AVRC_CT_METADATA_RSP_EVT: {
+        ESP_LOGI(BT_RC_CT_TAG, "AVRC metadata rsp: attribute id 0x%x, %s", rc->meta_rsp.attr_id, rc->meta_rsp.attr_text);
+        free(rc->meta_rsp.attr_text);
+        break;
+    }
+    case ESP_AVRC_CT_CHANGE_NOTIFY_EVT: {
+        ESP_LOGI(BT_RC_CT_TAG, "AVRC event notification: %d", rc->change_ntf.event_id);
+        bt_av_notify_evt_handler(rc->change_ntf.event_id, &rc->change_ntf.event_parameter);
+        break;
+    }
+    case ESP_AVRC_CT_REMOTE_FEATURES_EVT: {
+        ESP_LOGI(BT_RC_CT_TAG, "AVRC remote features %x, TG features %x", rc->rmt_feats.feat_mask, rc->rmt_feats.tg_feat_flag);
+        break;
+    }
+    case ESP_AVRC_CT_GET_RN_CAPABILITIES_RSP_EVT: {
+        ESP_LOGI(BT_RC_CT_TAG, "remote rn_cap: count %d, bitmask 0x%x", rc->get_rn_caps_rsp.cap_count,
+                 rc->get_rn_caps_rsp.evt_set.bits);
+        s_avrc_peer_rn_cap.bits = rc->get_rn_caps_rsp.evt_set.bits;
+
+        bt_av_volume_changed();
+        break;
+    }
+    case ESP_AVRC_CT_SET_ABSOLUTE_VOLUME_RSP_EVT: {
+        ESP_LOGI(BT_RC_CT_TAG, "Set absolute volume rsp: volume %d", rc->set_volume_rsp.volume);
+        break;
+    }
+
+    default:
+        ESP_LOGE(BT_RC_CT_TAG, "%s unhandled evt %d", __func__, event);
+        break;
+    }
+}

+ 6 - 1
components/squeezelite/CMakeLists.txt

@@ -1,3 +1,8 @@
+# for the forgetful, REQUIRES cannot use CONFIG_XXX due to parsing order
+if(IDF_TARGET STREQUAL "esp32")
+    set(target_requires "driver_bt")
+endif()
+
 idf_component_register( SRC_DIRS . external ac101 tas57xx wm8978
 						INCLUDE_DIRS .  ac101 
 						PRIV_REQUIRES 	
@@ -6,7 +11,6 @@ idf_component_register( SRC_DIRS . external ac101 tas57xx wm8978
 									esp_common 
 									esp-dsp
 						  			platform_config 
-						 			driver_bt 
 						 			services 
 									spotify
 						 			raop   
@@ -14,6 +18,7 @@ idf_component_register( SRC_DIRS . external ac101 tas57xx wm8978
 						 			tools
 						 			audio
 									_override
+						 			${target_requires}                                    
 						EMBED_FILES vu_s.data arrow.data
 )
 

+ 6 - 2
components/wifi-manager/CMakeLists.txt

@@ -1,10 +1,14 @@
-
 set( WEBPACK_DIR webapp/webpack/dist )
 
+# for the forgetful, REQUIRES cannot use CONFIG_XXX due to parsing order
+if(IDF_TARGET STREQUAL "esp32")
+    set(target_requires "driver_bt")
+endif()
+
 idf_component_register( SRC_DIRS . webapp UML-State-Machine-in-C/src
 						INCLUDE_DIRS . webapp UML-State-Machine-in-C/src
 						REQUIRES squeezelite-ota json mdns 
-						PRIV_REQUIRES tools services platform_config esp_common json newlib freertos spi_flash nvs_flash mdns pthread wpa_supplicant platform_console esp_http_server console driver_bt
+						PRIV_REQUIRES tools services platform_config esp_common json newlib freertos spi_flash nvs_flash mdns pthread wpa_supplicant platform_console esp_http_server console ${target_requires}
 )
 
 include(webapp/webapp.cmake)

+ 2 - 2
components/wifi-manager/network_status.c

@@ -4,7 +4,7 @@
 
 #include "network_status.h"
 #include <string.h>
-#ifdef BT_ENABLED
+#ifdef CONFIG_BT_ENABLED
 #include "bt_app_core.h"
 #endif
 #include "esp_log.h"
@@ -266,7 +266,7 @@ cJSON* network_status_get_basic_info(cJSON** old) {
         *old = network_status_update_float(old, "Voltage", battery_value_svc());
         *old = network_update_cjson_number(old, "disconnect_count", nm->num_disconnect);
         *old = network_status_update_float(old, "avg_conn_time", nm->num_disconnect > 0 ? (nm->total_connected_time / nm->num_disconnect) : 0);
-#ifdef BT_ENABLED        
+#ifdef CONFIG_BT_ENABLED        
         *old = network_update_cjson_number(old, "bt_status", bt_app_source_get_a2d_state());
         *old = network_update_cjson_number(old, "bt_sub_status", bt_app_source_get_media_state());
 #endif        

+ 1 - 4
main/CMakeLists.txt

@@ -1,7 +1,4 @@
 idf_component_register(SRC_DIRS . 
 					PRIV_REQUIRES _override esp_common wifi-manager pthread squeezelite-ota platform_console telnet display targets
-					LDFRAGMENTS "linker.lf"
+					LDFRAGMENTS "linker.lf"                                            
                     	)
-#get_target_property(ill ${COMPONENT_LIB} INTERFACE_LINK_LIBRARIES)
-#message("${COMPONENT_LIB} INTERFACE_LINK_LIBRARIES = ${ill}")
-

+ 5 - 0
main/esp_app_main.c

@@ -63,6 +63,11 @@ RTC_NOINIT_ATTR uint32_t RecoveryRebootCounter ;
 RTC_NOINIT_ATTR uint16_t ColdBootIndicatorFlag;
 bool cold_boot=true;
 
+#ifdef CONFIG_IDF_TARGET_ESP32S3
+extern const char _ctype_[];
+const char* __ctype_ptr__ = _ctype_;
+#endif
+
 static bool bNetworkConnected=false;
 
 // as an exception _init function don't need include

+ 4 - 1
main/linker.lf

@@ -1,4 +1,7 @@
 [mapping:cpp]
 archive: libstdc++.a
 entries:
-    * (extram_bss)
+    if IDF_TARGET = "esp32":
+       * (extram_bss)
+    else:
+       * (default)