浏览代码

ana_cmpr: designed driver layer

laokaiyao 2 年之前
父节点
当前提交
c634144ac8

+ 6 - 0
components/driver/CMakeLists.txt

@@ -10,6 +10,7 @@ set(srcs
 # Always included headers
 set(includes "include"
              "deprecated"
+             "analog_comparator/include"
              "dac/include"
              "gpio/include"
              "gptimer/include"
@@ -39,6 +40,11 @@ if(CONFIG_SOC_ADC_DMA_SUPPORTED)
     list(APPEND srcs "deprecated/adc_dma_legacy.c")
 endif()
 
+# Analog comparator related source files
+if(CONFIG_SOC_ANA_CMPR_SUPPORTED)
+    list(APPEND srcs "analog_comparator/ana_cmpr.c")
+endif()
+
 # DAC related source files
 if(CONFIG_SOC_DAC_SUPPORTED)
     list(APPEND srcs "dac/dac_oneshot.c"

+ 25 - 0
components/driver/Kconfig

@@ -274,6 +274,31 @@ menu "Driver Configurations"
                 Note that, this option only controls the SDM driver log, won't affect other drivers.
     endmenu # Sigma Delta Modulator Configuration
 
+    menu "Analog Comparator Configuration"
+        depends on SOC_ANA_CMPR_SUPPORTED
+        config ANA_CMPR_ISR_IRAM_SAFE
+            bool "Analog comparator ISR IRAM-Safe"
+            default n
+            help
+                Ensure the Analog Comparator interrupt is IRAM-Safe by allowing the interrupt handler to be
+                executable when the cache is disabled (e.g. SPI Flash write).
+
+        config ANA_CMPR_CTRL_FUNC_IN_IRAM
+            bool "Place Analog Comparator control functions into IRAM"
+            default n
+            help
+                Place Analog Comparator control functions (like set_intl_reference) into IRAM,
+                so that these functions can be IRAM-safe and able to be called in the other IRAM interrupt context.
+                Enabling this option can improve driver performance as well.
+
+        config ANA_CMPR_ENABLE_DEBUG_LOG
+            bool "Enable debug log"
+            default n
+            help
+                Wether to enable the debug log message for Analog Comparator driver.
+                Note that, this option only controls the Analog Comparator driver log, won't affect other drivers.
+    endmenu # Analog Comparator Configuration
+
     menu "GPTimer Configuration"
         config GPTIMER_CTRL_FUNC_IN_IRAM
             bool "Place GPTimer control functions into IRAM"

+ 0 - 54
components/driver/analog_cmpr/include/driver/analog_cmpr.h

@@ -1,54 +0,0 @@
-/*
- * SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
- *
- * SPDX-License-Identifier: Apache-2.0
- */
-#include <stdint.h>
-#include <stdbool.h>
-#include "esp_err.h"
-
-typedef struct analog_cmpr_t *analog_cmpr_handle_t;
-typedef struct analog_cmpr_ref_voltage_t *analog_cmpr_ref_voltage_handle_t;
-
-typedef struct {
-    analog_cmpr_ref_voltage_handle_t ref_volt;
-    struct {
-        uint32_t detect_pos: 1;
-        uint32_t detect_neg: 1;
-    } flags;
-} analog_cmpr_config_t;
-
-esp_err_t analog_cmpr_new_unit(const analog_cmpr_config_t *config, analog_cmpr_handle_t *ret_cmpr);
-
-typedef struct {
-    float ref_voltage;
-} analog_cmpr_internal_ref_voltage_config_t;
-
-typedef struct {
-    int ref_volt_gpio_num;
-} analog_cmpr_gpio_ref_voltage_config_t;
-
-esp_err_t analog_cmpr_new_gpio_ref_voltage(const analog_cmpr_gpio_ref_voltage_config_t *config, analog_cmpr_ref_voltage_handle_t *ret_ref_volt);
-
-esp_err_t analog_cmpr_new_internal_ref_voltage(const analog_cmpr_internal_ref_voltage_config_t *config, analog_cmpr_ref_voltage_handle_t *ret_ref_volt);
-
-typedef struct {
-
-} analog_cmpr_cross_event_data_t;
-
-typedef bool (*analog_cmpr_cross_cb_t) (analog_cmpr_handle_t cmpr, const analog_cmpr_cross_event_data_t *edata, void *user_ctx);
-
-typedef struct {
-    analog_cmpr_cross_cb_t on_cross;
-} analog_cmpr_event_callbacks_t;
-
-esp_err_t analog_cmpr_register_event_callbacks(analog_cmpr_handle_t cmpr, const analog_cmpr_event_callbacks_t *cbs, void *user_data);
-
-typedef struct {
-
-} analog_cmpr_debounce_filter_config_t;
-
-esp_err_t analog_cmpr_set_debounce_filter(analog_cmpr_handle_t cmpr, const analog_cmpr_debounce_filter_config_t *config);
-
-esp_err_t analog_cmpr_enable(analog_cmpr_handle_t cmpr);
-esp_err_t analog_cmpr_disable(analog_cmpr_handle_t cmpr);

+ 299 - 0
components/driver/analog_comparator/ana_cmpr.c

@@ -0,0 +1,299 @@
+/*
+ * SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
+
+#include <stdlib.h>
+#include <inttypes.h>
+#include "sdkconfig.h"
+#if CONFIG_SDM_ENABLE_DEBUG_LOG
+// The local log level must be defined before including esp_log.h
+// Set the maximum log level for this source file
+#define LOG_LOCAL_LEVEL ESP_LOG_DEBUG
+#endif
+#include "freertos/FreeRTOS.h"
+#include "clk_tree.h"
+#include "esp_types.h"
+#include "esp_attr.h"
+#include "esp_check.h"
+#include "esp_pm.h"
+#include "esp_heap_caps.h"
+#include "esp_intr_alloc.h"
+#include "soc/periph_defs.h"
+#include "soc/ana_cmpr_periph.h"
+#include "hal/ana_cmpr_ll.h"
+#include "driver/ana_cmpr.h"
+#include "esp_private/io_mux.h"
+#include "esp_private/esp_clk.h"
+
+struct ana_cmpr_t {
+    ana_cmpr_unit_t             unit;               /*!< Analog comparator unit id */
+    analog_cmpr_dev_t           *dev;               /*!< Analog comparator unit device address */
+    bool                        is_enabled;         /*!< Whether the Analog comparator unit is enabled */
+    ana_cmpr_event_callbacks_t  cbs;                /*!< The callback group that set by user */
+    intr_handle_t               intr_handle;        /*!< Interrupt handle */
+    void                        *user_data;         /*!< User data that passed to the callbacks */
+    uint32_t                    src_clk_freq_hz;    /*!< Source clock frequency of the Analog Comparator unit */
+    esp_pm_lock_handle_t        pm_lock;            /*!< The Power Management lock that used to avoid unexpected power down of the clock domain */
+};
+
+/* Helper macros */
+#define ANA_CMPR_NULL_POINTER_CHECK(p)      ESP_RETURN_ON_FALSE((p), ESP_ERR_INVALID_ARG, TAG, "input parameter '"#p"' is NULL")
+#define ANA_CMPR_NULL_POINTER_CHECK_ISR(p)  ESP_RETURN_ON_FALSE_ISR((p), ESP_ERR_INVALID_ARG, TAG, "input parameter '"#p"' is NULL")
+#define ANA_CMPR_UNIT_CHECK(unit)           ESP_RETURN_ON_FALSE((unit) >= ANA_CMPR_UNIT_0 && (unit) < SOC_ANA_CMPR_NUM, \
+                                                                ESP_ERR_INVALID_ARG, TAG, "invalid uint number");
+
+/* Memory allocation caps which decide the section that memory supposed to allocate */
+#if CONFIG_ANA_CMPR_ISR_IRAM_SAFE
+#define ANA_CMPR_MEM_ALLOC_CAPS      (MALLOC_CAP_INTERNAL | MALLOC_CAP_8BIT)
+#else
+#define ANA_CMPR_MEM_ALLOC_CAPS      MALLOC_CAP_DEFAULT
+#endif
+
+/* Driver tag */
+static const char *TAG = "ana_cmpr";
+
+/* Global static object of the Analog Comparator unit */
+static ana_cmpr_handle_t s_ana_cmpr[SOC_ANA_CMPR_NUM] = {
+    [0 ... (SOC_ANA_CMPR_NUM - 1)] = NULL,
+};
+
+/* Global spin lock */
+static portMUX_TYPE s_spinlock = portMUX_INITIALIZER_UNLOCKED;
+
+static void IRAM_ATTR s_ana_cmpr_default_intr_handler(void *usr_data)
+{
+    ana_cmpr_handle_t cmpr_handle = (ana_cmpr_handle_t)usr_data;
+    bool need_yield = false;
+    ana_cmpr_cross_event_data_t evt_data;
+    /* Get and clear the interrupt status */
+    uint32_t status = analog_cmpr_ll_get_intr_status(cmpr_handle->dev);
+    analog_cmpr_ll_clear_intr(cmpr_handle->dev, status);
+
+    /* Call the user callback function if it is specified and the corresponding event triggers*/
+    if (cmpr_handle->cbs.on_cross && (status & ANALOG_CMPR_LL_EVENT_CROSS)) {
+        need_yield = cmpr_handle->cbs.on_cross(cmpr_handle, &evt_data, cmpr_handle->user_data);
+    }
+    if (need_yield) {
+        portYIELD_FROM_ISR();
+    }
+}
+
+esp_err_t ana_cmpr_new_unit(const ana_cmpr_config_t *config, ana_cmpr_handle_t *ret_cmpr)
+{
+#if CONFIG_SDM_ENABLE_DEBUG_LOG
+    esp_log_level_set(TAG, ESP_LOG_DEBUG);
+#endif
+    ANA_CMPR_NULL_POINTER_CHECK(config);
+    ANA_CMPR_NULL_POINTER_CHECK(ret_cmpr);
+    ana_cmpr_unit_t unit = config->unit;
+    ANA_CMPR_UNIT_CHECK(unit);
+    ESP_RETURN_ON_FALSE(!s_ana_cmpr[unit], ESP_ERR_INVALID_STATE, TAG,
+                        "unit has been allocated already");
+    esp_err_t ret = ESP_OK;
+
+    /* Allocate analog comparator unit */
+    s_ana_cmpr[unit] = (ana_cmpr_handle_t)heap_caps_calloc(1, sizeof(struct ana_cmpr_t), ANA_CMPR_MEM_ALLOC_CAPS);
+    ESP_RETURN_ON_FALSE(s_ana_cmpr[unit], ESP_ERR_NO_MEM, TAG, "no memory for analog comparator struct");
+
+    /* Assign analog comparator unit */
+    s_ana_cmpr[unit]->dev = ANALOG_CMPR_LL_GET_HW();
+    s_ana_cmpr[unit]->is_enabled = false;
+    s_ana_cmpr[unit]->pm_lock = NULL;
+
+#if CONFIG_PM_ENABLE
+    /* Create PM lock */
+    char lock_name[10] = "ana_cmpr\0";
+    lock_name[8] = '0' + unit;
+    ret  = esp_pm_lock_create(ESP_PM_NO_LIGHT_SLEEP, 0, lock_name, &s_ana_cmpr[unit]->pm_lock);
+    ESP_GOTO_ON_ERROR(ret, err, TAG, "create NO_LIGHT_SLEEP, lock failed");
+#endif
+
+    /* Analog clock comes from IO MUX, but IO MUX clock might be shared with other submodules as well */
+    ESP_GOTO_ON_ERROR(clk_tree_src_get_freq_hz((soc_module_clk_t)config->clk_src,
+                                                CLK_TREE_SRC_FREQ_PRECISION_CACHED,
+                                                &s_ana_cmpr[unit]->src_clk_freq_hz),
+                                                err, TAG, "get source clock frequency failed");
+    ESP_GOTO_ON_ERROR(io_mux_set_clock_source((soc_module_clk_t)(config->clk_src)), err, TAG, "set IO MUX clock source failed");
+
+    /* Configure the register */
+    portENTER_CRITICAL(&s_spinlock);
+    analog_cmpr_ll_ref_source(s_ana_cmpr[unit]->dev, config->ref_src);
+    analog_cmpr_ll_set_cross_intr_type(s_ana_cmpr[unit]->dev, config->intr_type);
+    portEXIT_CRITICAL(&s_spinlock);
+
+    /* Allocate the interrupt, currently the interrupt source of Analog Comparator is shared with GPIO interrupt source */
+    esp_intr_alloc(ETS_GPIO_INTR_SOURCE, ESP_INTR_FLAG_LEVEL1,
+                   s_ana_cmpr_default_intr_handler, s_ana_cmpr[unit], &s_ana_cmpr[unit]->intr_handle);
+
+    if (config->ref_src == ANA_CMPR_REF_SRC_INTERNAL) {
+        ESP_LOGD(TAG, "unit %d allocated, source signal: GPIO %d, reference signal: internal",
+                 (int)unit, ana_cmpr_io_map[unit].src_gpio);
+    } else {
+        ESP_LOGD(TAG, "unit %d allocated, source signal: GPIO %d, reference signal: GPIO %d",
+                 (int)unit, ana_cmpr_io_map[unit].src_gpio, ana_cmpr_io_map[unit].ext_ref_gpio);
+    }
+
+    *ret_cmpr = s_ana_cmpr[unit];
+    return ESP_OK;
+
+err:
+    /* Free the resources if allocation failed */
+    free(s_ana_cmpr[unit]);
+    s_ana_cmpr[unit] = NULL;
+    return ret;
+}
+
+esp_err_t ana_cmpr_del_unit(ana_cmpr_handle_t cmpr)
+{
+    ANA_CMPR_NULL_POINTER_CHECK(cmpr);
+    /* Search the global object array to check if the input handle is valid */
+    ana_cmpr_unit_t unit = -1;
+    for (int i = 0; i < SOC_ANA_CMPR_NUM; i++) {
+        if (s_ana_cmpr[i] == cmpr) {
+            unit = i;
+            break;
+        }
+    }
+    ESP_RETURN_ON_FALSE(unit >= ANA_CMPR_UNIT_0, ESP_ERR_INVALID_ARG, TAG, "wrong analog comparator handle");
+    ESP_RETURN_ON_FALSE(!cmpr->is_enabled, ESP_ERR_INVALID_STATE, TAG, "this analog comparator unit not disabled yet");
+
+    /* Disable the Analog Comparator interrupt */
+    portENTER_CRITICAL(&s_spinlock);
+    analog_cmpr_ll_enable_intr(cmpr->dev, ANALOG_CMPR_LL_EVENT_CROSS, false);
+    portEXIT_CRITICAL(&s_spinlock);
+
+    /* Delete the pm lock if the unit has */
+    if (cmpr->pm_lock) {
+        ESP_RETURN_ON_ERROR(esp_pm_lock_delete(cmpr->pm_lock), TAG, "delete pm lock failed");
+    }
+
+    /* Free interrupt and other resources */
+    esp_intr_free(cmpr->intr_handle);
+    free(s_ana_cmpr[unit]);
+    s_ana_cmpr[unit] = NULL;
+
+    ESP_LOGD(TAG, "unit %d deleted", (int)unit);
+
+    return ESP_OK;
+}
+
+esp_err_t ana_cmpr_set_intl_reference(ana_cmpr_handle_t cmpr, const ana_cmpr_intl_ref_config_t *ref_cfg)
+{
+    ANA_CMPR_NULL_POINTER_CHECK_ISR(cmpr);
+    ANA_CMPR_NULL_POINTER_CHECK_ISR(ref_cfg);
+
+    /* Set internal reference voltage */
+    portENTER_CRITICAL_ISR(&s_spinlock);
+    analog_cmpr_ll_set_internal_ref_voltage(cmpr->dev, ref_cfg->ref_volt);
+    portEXIT_CRITICAL_ISR(&s_spinlock);
+
+    ESP_EARLY_LOGD(TAG, "unit %d internal voltage level %"PRIu32, (int)cmpr->unit, ref_cfg->ref_volt);
+
+    return ESP_OK;
+}
+
+esp_err_t ana_cmpr_set_debounce(ana_cmpr_handle_t cmpr, const ana_cmpr_debounce_config_t *dbc_cfg)
+{
+    ANA_CMPR_NULL_POINTER_CHECK_ISR(cmpr);
+    ANA_CMPR_NULL_POINTER_CHECK_ISR(dbc_cfg);
+
+    /* Transfer the time to clock cycles */
+    uint32_t wait_cycle = (uint32_t)(dbc_cfg->wait_us * cmpr->src_clk_freq_hz) / 1000000;
+    /* Set the waiting clock cycles */
+    portENTER_CRITICAL_ISR(&s_spinlock);
+    analog_cmpr_ll_set_debounce_cycle(cmpr->dev, wait_cycle);
+    portEXIT_CRITICAL_ISR(&s_spinlock);
+
+    ESP_EARLY_LOGD(TAG, "unit %d debounce wait cycle %"PRIu32, (int)cmpr->unit, wait_cycle);
+
+    return ESP_OK;
+}
+
+esp_err_t ana_cmpr_register_event_callbacks(ana_cmpr_handle_t cmpr, const ana_cmpr_event_callbacks_t *cbs, void *user_data)
+{
+    ANA_CMPR_NULL_POINTER_CHECK(cmpr);
+    ANA_CMPR_NULL_POINTER_CHECK(cbs);
+    ESP_RETURN_ON_FALSE(!cmpr->is_enabled, ESP_ERR_INVALID_STATE, TAG,
+                        "please disable the analog comparator before registering the callbacks");
+
+    /* Save the callback group */
+    memcpy(&(cmpr->cbs), cbs, sizeof(ana_cmpr_event_callbacks_t));
+    cmpr->user_data = user_data;
+
+    /* Enable the Analog Comparator interrupt */
+    portENTER_CRITICAL(&s_spinlock);
+    analog_cmpr_ll_enable_intr(cmpr->dev, ANALOG_CMPR_LL_EVENT_CROSS, !!(cbs->on_cross));
+    portEXIT_CRITICAL(&s_spinlock);
+
+    ESP_LOGD(TAG, "unit %d event callback registered", (int)cmpr->unit);
+
+    return ESP_OK;
+}
+
+esp_err_t ana_cmpr_enable(ana_cmpr_handle_t cmpr)
+{
+    ANA_CMPR_NULL_POINTER_CHECK(cmpr);
+    ESP_RETURN_ON_FALSE(!cmpr->is_enabled, ESP_ERR_INVALID_STATE, TAG,
+                        "the analog comparator has enabled already");
+    /* Update the driver status */
+    cmpr->is_enabled = true;
+
+    /* Acquire the pm lock if the unit has, to avoid the system start light sleep while Analog comparator still working */
+    if (cmpr->pm_lock) {
+        ESP_RETURN_ON_ERROR(esp_pm_lock_acquire(cmpr->pm_lock), TAG, "acquire pm_lock failed");
+    }
+
+    /* Enable the Analog Comparator */
+    portENTER_CRITICAL(&s_spinlock);
+    analog_cmpr_ll_enable(cmpr->dev, true);
+    portEXIT_CRITICAL(&s_spinlock);
+
+    ESP_LOGD(TAG, "unit %d enabled", (int)cmpr->unit);
+
+    return ESP_OK;
+}
+
+esp_err_t ana_cmpr_disable(ana_cmpr_handle_t cmpr)
+{
+    ANA_CMPR_NULL_POINTER_CHECK(cmpr);
+    ESP_RETURN_ON_FALSE(cmpr->is_enabled, ESP_ERR_INVALID_STATE, TAG,
+                        "the analog comparator not enabled yet");
+    /* Disable the Analog Comparator */
+    portENTER_CRITICAL(&s_spinlock);
+    analog_cmpr_ll_enable(cmpr->dev, false);
+    portEXIT_CRITICAL(&s_spinlock);
+
+    /* Release the pm lock, allow light sleep then */
+    if (cmpr->pm_lock) {
+        ESP_RETURN_ON_ERROR(esp_pm_lock_release(cmpr->pm_lock), TAG, "release pm_lock failed");
+    }
+
+    /* Update the driver status */
+    cmpr->is_enabled = false;
+
+    ESP_LOGD(TAG, "unit %d disabled", (int)cmpr->unit);
+    return ESP_OK;
+}
+
+esp_err_t ana_cmpr_get_gpio(ana_cmpr_unit_t unit, ana_cmpr_channel_type_t chan_type, int *gpio_num)
+{
+    ANA_CMPR_NULL_POINTER_CHECK(gpio_num);
+    ANA_CMPR_UNIT_CHECK(unit);
+
+    /* Get the gpio number according to the channel type */
+    switch (chan_type) {
+    case ANA_CMPR_SOURCE_CHAN:
+        *gpio_num = ana_cmpr_io_map[unit].src_gpio;
+        break;
+    case ANA_CMPR_EXT_REF_CHAN:
+        *gpio_num = ana_cmpr_io_map[unit].ext_ref_gpio;
+        break;
+    default:
+        ESP_LOGE(TAG, "invalid channel type");
+        return ESP_ERR_INVALID_ARG;
+    }
+
+    return ESP_OK;
+}

+ 169 - 0
components/driver/analog_comparator/include/driver/ana_cmpr.h

@@ -0,0 +1,169 @@
+/*
+ * SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
+#include <stdint.h>
+#include <stdbool.h>
+#include "esp_err.h"
+#include "driver/ana_cmpr_types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @brief Analog comparator unit configuration
+ *
+ */
+typedef struct {
+    ana_cmpr_unit_t         unit;               /*!< Analog comparator unit */
+    ana_cmpr_clk_src_t      clk_src;            /*!< The clock source of the analog comparator,
+                                                 *   which decide the resolution of the comparator
+                                                 */
+    ana_cmpr_ref_source_t   ref_src;            /*!< Reference signal source of the comparator,
+                                                 *   select using ANA_CMPR_REF_SRC_INTERNAL or ANA_CMPR_REF_SRC_EXTERNAL.
+                                                 *   For internal reference, the reference voltage should be set to `internal_ref_volt`,
+                                                 *   for external reference, the reference signal should be connect to `ANA_CMPRx_EXT_REF_GPIO`
+                                                 */
+    ana_cmpr_intr_type_t    intr_type;          /*!< The crossing types that can trigger interrupt */
+} ana_cmpr_config_t;
+
+/**
+ * @brief Analog comparator internal reference configuration
+ *
+ */
+typedef struct {
+    ana_cmpr_ref_voltage_t  ref_volt;           /*!< The internal reference voltage. It can specify several dozen percent from the VDD power supply,
+                                                 *   currently supports 0%~70% VDD with step 10%
+                                                 */
+} ana_cmpr_intl_ref_config_t;
+
+/**
+ * @brief Analog comparator debounce filter configuration
+ *
+ */
+typedef struct {
+    float                   wait_us;            /*!< The wait time of re-enabling the interrupt after the last triggering,
+                                                 *   it is used to avoid the spurious triggering while the source signal crossing the reference signal.
+                                                 *   The value should regarding how fast the source signal changes, e.g., a rapid signal requires
+                                                 *   a small wait time, otherwise the next crosses may be missed.
+                                                 *   (Unit: micro second, resolution = 1 / SRC_CLK_FREQ)
+                                                 */
+} ana_cmpr_debounce_config_t;
+
+/**
+ * @brief Group of Analog Comparator callbacks
+ * @note The callbacks are all running under ISR environment
+ * @note When CONFIG_ANA_CMPR_ISR_IRAM_SAFE is enabled, the callback itself and functions called by it should be placed in IRAM.
+ *       The variables used in the function should be in the SRAM as well.
+ */
+typedef struct {
+    ana_cmpr_cross_cb_t on_cross;               /*!< The callback function on cross interrupt */
+} ana_cmpr_event_callbacks_t;
+
+/**
+ * @brief Allocating a new analog comparator unit handle
+ *
+ * @param[in]  config       The config of the analog comparator unit
+ * @param[out] ret_cmpr     The returned analog comparator unit handle
+ * @return
+ *      - ESP_OK                Allocate analog comparator unit handle success
+ *      - ESP_ERR_NO_MEM        No memory for the analog comparator structure
+ *      - ESP_ERR_INVALID_ARG   NULL pointer of the parameters or wrong unit number
+ *      - ESP_ERR_INVALID_STATE The unit has been allocated or the clock source has been occupied
+ */
+esp_err_t ana_cmpr_new_unit(const ana_cmpr_config_t *config, ana_cmpr_handle_t *ret_cmpr);
+
+/**
+ * @brief Delete the analog comparator unit handle
+ *
+ * @param[in]  cmpr         The handle of analog comparator unit
+ * @return
+ *      - ESP_OK                Delete analog comparator unit handle success
+ *      - ESP_ERR_INVALID_ARG   NULL pointer of the parameters or wrong unit number
+ *      - ESP_ERR_INVALID_STATE The analog comparator is not disabled yet
+ */
+esp_err_t ana_cmpr_del_unit(ana_cmpr_handle_t cmpr);
+
+/**
+ * @brief Set internal reference configuration
+ * @note  This function only need to be called when `ana_cmpr_config_t::ref_src`
+ *        is ANA_CMPR_REF_SRC_INTERNAL.
+ * @note This function is allowed to run within ISR context including intr callbacks
+ * @note This function will be placed into IRAM if `CONFIG_ANA_CMPR_CTRL_FUNC_IN_IRAM` is on,
+ *       so that it's allowed to be executed when Cache is disabled
+ *
+ * @param[in]  cmpr         The handle of analog comparator unit
+ * @param[in]  ref_cfg      Internal reference configuration
+ * @return
+ *      - ESP_OK                Set denounce configuration success
+ *      - ESP_ERR_INVALID_ARG   NULL pointer of the parameters
+ */
+esp_err_t ana_cmpr_set_intl_reference(ana_cmpr_handle_t cmpr, const ana_cmpr_intl_ref_config_t *ref_cfg);
+
+/**
+ * @brief Set debounce configuration to the analog comparator
+ * @note This function is allowed to run within ISR context including intr callbacks
+ * @note This function will be placed into IRAM if `CONFIG_ANA_CMPR_CTRL_FUNC_IN_IRAM` is on,
+ *       so that it's allowed to be executed when Cache is disabled
+ *
+ * @param[in]  cmpr         The handle of analog comparator unit
+ * @param[in]  dbc_cfg      Debounce configuration
+ * @return
+ *      - ESP_OK                Set denounce configuration success
+ *      - ESP_ERR_INVALID_ARG   NULL pointer of the parameters
+ */
+esp_err_t ana_cmpr_set_debounce(ana_cmpr_handle_t cmpr, const ana_cmpr_debounce_config_t *dbc_cfg);
+
+/**
+ * @brief Register analog comparator interrupt event callbacks
+ * @note  This function can only be called before enabling the unit
+ *
+ * @param[in]  cmpr         The handle of analog comparator unit
+ * @param[in]  cbs          Group of callback functions
+ * @param[in]  user_data    The user data that will be passed to callback functions directly
+ * @return
+ *      - ESP_OK                Register callbacks success
+ *      - ESP_ERR_INVALID_ARG   NULL pointer of the parameters
+ *      - ESP_ERR_INVALID_STATE The analog comparator has been enabled
+ */
+esp_err_t ana_cmpr_register_event_callbacks(ana_cmpr_handle_t cmpr, const ana_cmpr_event_callbacks_t *cbs, void *user_data);
+
+/**
+ * @brief Enable the analog comparator unit
+ *
+ * @param[in]  cmpr         The handle of analog comparator unit
+ * @return
+ *      - ESP_OK                Enable analog comparator unit success
+ *      - ESP_ERR_INVALID_ARG   NULL pointer of the parameters
+ *      - ESP_ERR_INVALID_STATE The analog comparator has been enabled
+ */
+esp_err_t ana_cmpr_enable(ana_cmpr_handle_t cmpr);
+
+/**
+ * @brief Disable the analog comparator unit
+ *
+ * @param[in]  cmpr         The handle of analog comparator unit
+ * @return
+ *      - ESP_OK                Disable analog comparator unit success
+ *      - ESP_ERR_INVALID_ARG   NULL pointer of the parameters
+ *      - ESP_ERR_INVALID_STATE The analog comparator has disabled already
+ */
+esp_err_t ana_cmpr_disable(ana_cmpr_handle_t cmpr);
+
+/**
+ * @brief Get the specific GPIO number of the analog comparator unit
+ *
+ * @param[in]  unit         The handle of analog comparator unit
+ * @param[in]  chan_type    The channel type of analog comparator, like source channel or reference channel
+ * @param[out] gpio_num     The output GPIO number of this channel
+ * @return
+ *      - ESP_OK                Get GPIO success
+ *      - ESP_ERR_INVALID_ARG   NULL pointer of the parameters or wrong unit number or wrong channel type
+ */
+esp_err_t ana_cmpr_get_gpio(ana_cmpr_unit_t unit, ana_cmpr_channel_type_t chan_type, int *gpio_num);
+
+#ifdef __cplusplus
+}
+#endif

+ 109 - 0
components/driver/analog_comparator/include/driver/ana_cmpr_types.h

@@ -0,0 +1,109 @@
+/*
+ * SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
+
+#pragma once
+
+#include <stdbool.h>
+#include "soc/clk_tree_defs.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @brief Analog comparator unit
+ *
+ */
+typedef enum {
+    ANA_CMPR_UNIT_0,                /*!< Analog Comparator unit */
+} ana_cmpr_unit_t;
+
+/**
+ * @brief Analog comparator reference source
+ *
+ */
+typedef enum {
+    ANA_CMPR_REF_SRC_INTERNAL,      /*!< Analog Comparator internal reference source, related to VDD */
+    ANA_CMPR_REF_SRC_EXTERNAL,      /*!< Analog Comparator external reference source, from `ANA_CMPR0_EXT_REF_GPIO` */
+} ana_cmpr_ref_source_t;
+
+/**
+ * @brief Analog comparator channel type
+ *
+ */
+typedef enum {
+    ANA_CMPR_SOURCE_CHAN,           /*!< Analog Comparator source channel, which is used to input the signal that to be compared */
+    ANA_CMPR_EXT_REF_CHAN,          /*!< Analog Comparator external reference channel, which is used as the reference signal */
+} ana_cmpr_channel_type_t;
+
+/**
+ * @brief Analog comparator interrupt type
+ *
+ */
+typedef enum {
+    ANA_CMPR_INTR_DISABLE,          /*!< Disable the cross event interrupt */
+    ANA_CMPR_INTR_POS_CROSS,        /*!< Enable the positive cross event interrupt */
+    ANA_CMPR_INTR_NEG_CROSS,        /*!< Enable the negative cross event interrupt */
+    ANA_CMPR_INTR_ANY_CROSS,        /*!< Enable the both positive & negative cross event interrupt */
+} ana_cmpr_intr_type_t;
+
+/**
+ * @brief Analog comparator internal reference voltage
+ *
+ */
+typedef enum {
+    ANA_CMPR_REF_VOLT_0_PCT_VDD,    /*!< Internal reference voltage equals to 0% VDD */
+    ANA_CMPR_REF_VOLT_10_PCT_VDD,   /*!< Internal reference voltage equals to 10% VDD */
+    ANA_CMPR_REF_VOLT_20_PCT_VDD,   /*!< Internal reference voltage equals to 20% VDD */
+    ANA_CMPR_REF_VOLT_30_PCT_VDD,   /*!< Internal reference voltage equals to 30% VDD */
+    ANA_CMPR_REF_VOLT_40_PCT_VDD,   /*!< Internal reference voltage equals to 40% VDD */
+    ANA_CMPR_REF_VOLT_50_PCT_VDD,   /*!< Internal reference voltage equals to 50% VDD */
+    ANA_CMPR_REF_VOLT_60_PCT_VDD,   /*!< Internal reference voltage equals to 60% VDD */
+    ANA_CMPR_REF_VOLT_70_PCT_VDD,   /*!< Internal reference voltage equals to 70% VDD */
+} ana_cmpr_ref_voltage_t;
+
+/**
+ * @brief Analog comparator unit handle
+ *
+ */
+typedef struct ana_cmpr_t *ana_cmpr_handle_t;
+
+#if SOC_ANA_CMPR_SUPPORTED
+/**
+ * @brief Analog comparator clock source
+ *
+ */
+typedef soc_periph_ana_cmpr_clk_src_t ana_cmpr_clk_src_t;
+#else
+/**
+ * @brief Analog comparator clock source
+ *
+ */
+typedef int ana_cmpr_clk_src_t;
+#endif
+
+/**
+ * @brief Analog comparator cross event data
+ *
+ */
+typedef struct {
+    // Currently no data
+} ana_cmpr_cross_event_data_t;
+
+/**
+ * @brief Prototype of Analog comparator event callback
+ * @param[in] cmpr  Analog Comparator handle, created from `ana_cmpr_new_unit()`
+ * @param[in] edata Point to Analog Comparator event data. The lifecycle of this pointer memory is inside this function,
+ *                  user should copy it into static memory if used outside this function. (Currently not use)
+ * @param[in] user_ctx User registered context, passed from `ana_cmpr_register_event_callbacks()`
+ *
+ * @return Whether a high priority task has been waken up by this callback function
+ */
+typedef bool (*ana_cmpr_cross_cb_t) (ana_cmpr_handle_t cmpr, const ana_cmpr_cross_event_data_t *edata, void *user_ctx);
+
+#ifdef __cplusplus
+}
+#endif

+ 3 - 0
components/driver/linker.lf

@@ -18,6 +18,9 @@ entries:
         gpio: gpio_intr_disable (noflash)
     if SDM_CTRL_FUNC_IN_IRAM = y:
         sdm: sdm_channel_set_pulse_density (noflash)
+    if ANA_CMPR_CTRL_FUNC_IN_IRAM = y:
+        ana_cmpr: ana_cmpr_set_intl_reference (noflash)
+        ana_cmpr: ana_cmpr_set_debounce (noflash)
     if DAC_CTRL_FUNC_IN_IRAM = y:
         dac_oneshot: dac_oneshot_output_voltage (noflash)
         dac_continuous: dac_continuous_write_asynchronously (noflash)

+ 0 - 4
components/hal/CMakeLists.txt

@@ -97,10 +97,6 @@ if(NOT BOOTLOADER_BUILD)
         list(APPEND srcs "sdm_hal.c")
     endif()
 
-    if(CONFIG_SOC_ANALOG_CMPR_SUPPORTED)
-        list(APPEND srcs "analog_cmpr_hal.c")
-    endif()
-
     if(CONFIG_ETH_USE_ESP32_EMAC)
         list(APPEND srcs "emac_hal.c")
     endif()

+ 0 - 13
components/hal/analog_cmpr_hal.c

@@ -1,13 +0,0 @@
-/*
- * SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
- *
- * SPDX-License-Identifier: Apache-2.0
- */
-
-#include "hal/analog_cmpr_ll.h"
-#include "hal/analog_cmpr_hal.h"
-
-void analog_cmpr_hal_init(analog_cmpr_hal_context_t *hal)
-{
-    hal->dev = ANALOG_CMPR_LL_GET_HW();
-}

+ 22 - 46
components/hal/esp32h2/include/hal/analog_cmpr_ll.h → components/hal/esp32h2/include/hal/ana_cmpr_ll.h

@@ -11,8 +11,11 @@
 #include "hal/assert.h"
 #include "soc/gpio_ext_struct.h"
 
-#define ANALOG_CMPR_LL_GET_HW()    (&ANALOG_CMPR)
-#define ANALOG_CMPR_LL_EVENT_CROSS (1 << 0)
+#define ANALOG_CMPR_LL_GET_HW()         (&ANALOG_CMPR)
+#define ANALOG_CMPR_LL_EVENT_CROSS      (1 << 0)
+
+#define ANALOG_CMPR_LL_POS_CROSS_MASK   (1 << 1)
+#define ANALOG_CMPR_LL_NEG_CROSS_MASK   (1 << 2)
 
 #ifdef __cplusplus
 extern "C" {
@@ -33,14 +36,11 @@ static inline void analog_cmpr_ll_enable(analog_cmpr_dev_t *hw, bool en)
  * @brief Set the voltage of the internal reference
  *
  * @param hw Analog comparator register base address
- * @param voltage The voltage of the internal reference, range [0.0V, 0.7VDD], step 0.1VDD
+ * @param volt_level The voltage level of the internal reference, range [0.0V, 0.7VDD], step 0.1VDD
  */
-static inline void analog_cmpr_ll_set_internal_ref_voltage(analog_cmpr_dev_t *hw, float voltage)
+static inline void analog_cmpr_ll_set_internal_ref_voltage(analog_cmpr_dev_t *hw, uint32_t volt_level)
 {
-    hw->pad_comp_config.mode_comp = 0;
-    uint32_t volt_reg_val = (uint32_t)((voltage + 0.05F) / 0.1F);
-    HAL_ASSERT(volt_reg_val <= 7);
-    hw->pad_comp_config.dref_comp = volt_reg_val;
+    hw->pad_comp_config.dref_comp = volt_level;
 }
 
 /**
@@ -55,55 +55,31 @@ static inline float analog_cmpr_ll_get_internal_ref_voltage(analog_cmpr_dev_t *h
 }
 
 /**
- * @brief The reference voltage comes from GPIO pad (GPIO10)
+ * @brief The reference voltage comes from internal or external
  *
  * @note Also see `analog_cmpr_ll_set_internal_ref_voltage` to use the internal reference voltage
  *
  * @param hw Analog comparator register base address
+ * @param ref_src reference source, 0 for internal, 1 for external GPIO pad (GPIO10)
  */
-static inline void analog_cmpr_ll_ref_voltage_from_external(analog_cmpr_dev_t *hw)
-{
-    hw->pad_comp_config.mode_comp = 1;
-}
-
-/**
- * @brief Disable the cross detection
- *
- * @param hw Analog comparator register base address
- */
-static inline void analog_cmpr_ll_disable_cross_detection(analog_cmpr_dev_t *hw)
+static inline void analog_cmpr_ll_ref_source(analog_cmpr_dev_t *hw, uint32_t ref_src)
 {
-    hw->pad_comp_config.zero_det_mode = 0;
+    hw->pad_comp_config.mode_comp = ref_src;
 }
 
 /**
- * @brief Enable to detect the positive cross (input analog goes from low to high and across the reference voltage)
+ * @brief Set cross interrupt trigger type
  *
  * @param hw Analog comparator register base address
- * @param enable True to enable, False to disable
+ * @param type The type of cross interrupt
+ *              - 0: disable interrupt
+ *              - 1: enable positive cross interrupt (input analog goes from low to high and across the reference voltage)
+ *              - 2: enable negative cross interrupt (input analog goes from high to low and across the reference voltage)
+ *              - 3: enable any positive or negative cross interrupt
  */
-static inline void analog_cmpr_ll_enable_pos_cross_detection(analog_cmpr_dev_t *hw, bool enable)
+static inline void analog_cmpr_ll_set_cross_intr_type(analog_cmpr_dev_t *hw, uint8_t type)
 {
-    if (enable) {
-        hw->pad_comp_config.zero_det_mode |= (1 << 0);
-    } else {
-        hw->pad_comp_config.zero_det_mode &= ~(1 << 0);
-    }
-}
-
-/**
- * @brief Enable to detect the negative cross (input analog goes from high to low and across the reference voltage)
- *
- * @param hw Analog comparator register base address
- * @param enable True to enable, False to disable
- */
-static inline void analog_cmpr_ll_enable_neg_cross_detection(analog_cmpr_dev_t *hw, bool enable)
-{
-    if (enable) {
-        hw->pad_comp_config.zero_det_mode |= (1 << 1);
-    } else {
-        hw->pad_comp_config.zero_det_mode &= ~(1 << 1);
-    }
+    hw->pad_comp_config.zero_det_mode = type;
 }
 
 /**
@@ -140,9 +116,9 @@ static inline void analog_cmpr_ll_enable_intr(analog_cmpr_dev_t *hw, uint32_t ma
  *
  * @param hw Analog comparator register base address
  */
-static inline void analog_cmpr_ll_get_intr_status(analog_cmpr_dev_t *hw)
+static inline uint32_t analog_cmpr_ll_get_intr_status(analog_cmpr_dev_t *hw)
 {
-    hw->int_st.val;
+    return hw->int_st.val;
 }
 
 /**

+ 0 - 37
components/hal/include/hal/analog_cmpr_hal.h

@@ -1,37 +0,0 @@
-/*
- * SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
- *
- * SPDX-License-Identifier: Apache-2.0
- */
-
-/*******************************************************************************
- * NOTICE
- * The hal is not public api, don't use in application code.
- * See readme.md in hal/include/hal/readme.md
- ******************************************************************************/
-
-#pragma once
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-typedef struct analog_cmpr_dev_t *analog_cmpr_handle_t; // Analog comparator SOC layer handle
-
-/**
- * HAL context type of analog comparator driver
- */
-typedef struct {
-    analog_cmpr_handle_t dev;
-} analog_cmpr_hal_context_t;
-
-/**
- * @brief Initialize Analog comparator hal driver
- *
- * @param hal Context of the HAL layer
- */
-void analog_cmpr_hal_init(analog_cmpr_hal_context_t *hal);
-
-#ifdef __cplusplus
-}
-#endif

+ 4 - 0
components/soc/CMakeLists.txt

@@ -30,6 +30,10 @@ if(CONFIG_SOC_ADC_SUPPORTED)
     list(APPEND srcs "${target}/adc_periph.c")
 endif()
 
+if(CONFIG_SOC_ANA_CMPR_SUPPORTED)
+    list(APPEND srcs "${target}/ana_cmpr_periph.c")
+endif()
+
 if(CONFIG_SOC_DEDICATED_GPIO_SUPPORTED)
     list(APPEND srcs "${target}/dedic_gpio_periph.c")
 endif()

+ 14 - 0
components/soc/esp32h2/ana_cmpr_periph.c

@@ -0,0 +1,14 @@
+/*
+ * SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
+
+#include "soc/ana_cmpr_periph.h"
+
+const ana_cmpr_conn_t ana_cmpr_io_map[SOC_ANA_CMPR_NUM] = {
+    [0] = {
+        .src_gpio = ANA_CMPR0_SRC_GPIO,
+        .ext_ref_gpio = ANA_CMPR0_EXT_REF_GPIO,
+    },
+};

+ 8 - 0
components/soc/esp32h2/include/soc/Kconfig.soc_caps.in

@@ -7,6 +7,10 @@ config SOC_ADC_SUPPORTED
     bool
     default y
 
+config SOC_ANA_CMPR_SUPPORTED
+    bool
+    default y
+
 config SOC_DEDICATED_GPIO_SUPPORTED
     bool
     default y
@@ -423,6 +427,10 @@ config SOC_DEDIC_PERIPH_ALWAYS_ENABLE
     bool
     default y
 
+config SOC_ANA_CMPR_NUM
+    int
+    default 1
+
 config SOC_I2C_NUM
     int
     default 2

+ 10 - 0
components/soc/esp32h2/include/soc/ana_cmpr_channel.h

@@ -0,0 +1,10 @@
+/*
+ * SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
+
+#pragma once
+
+#define ANA_CMPR0_EXT_REF_GPIO    10      /*!< The GPIO that can be used as external reference voltage */
+#define ANA_CMPR0_SRC_GPIO        11      /*!< The GPIO that used for inputting the source signal to compare */

+ 16 - 0
components/soc/esp32h2/include/soc/clk_tree_defs.h

@@ -330,6 +330,22 @@ typedef enum {
     SDM_CLK_SRC_DEFAULT = SOC_MOD_CLK_PLL_F48M,                 /*!< Select PLL_F48M as the default clock choice */
 } soc_periph_sdm_clk_src_t;
 
+///////////////////////////////////////////////////Analog Comparator////////////////////////////////////////////////////
+
+/**
+ * @brief Array initializer for all supported clock sources of Analog Comparator
+ */
+#define SOC_ANA_CMPR_CLKS {SOC_MOD_CLK_PLL_F48M, SOC_MOD_CLK_XTAL}
+
+/**
+ * @brief Sigma Delta Modulator clock source
+ */
+typedef enum {
+    ANA_CMPR_CLK_SRC_XTAL = SOC_MOD_CLK_XTAL,                   /*!< Select XTAL clock as the source clock */
+    ANA_CMPR_CLK_SRC_PLL_F48M = SOC_MOD_CLK_PLL_F48M,           /*!< Select PLL_F48M clock as the source clock */
+    ANA_CMPR_CLK_SRC_DEFAULT = SOC_MOD_CLK_PLL_F48M,            /*!< Select PLL_F48M as the default clock choice */
+} soc_periph_ana_cmpr_clk_src_t;
+
 //////////////////////////////////////////////////GPIO Glitch Filter////////////////////////////////////////////////////
 
 /**

+ 2 - 2
components/soc/esp32h2/include/soc/gpio_ext_struct.h

@@ -75,8 +75,8 @@ typedef union {
          */
         uint32_t xpd_comp:1;
         /** mode_comp : R/W; bitpos: [1]; default: 0;
-         *  1 to enable external reference from PAD[0]. 0 to enable internal reference,
-         *  meanwhile PAD[0] can be used as a regular GPIO.
+         *  1 to enable external reference from PAD[10]. 0 to enable internal reference,
+         *  meanwhile PAD[10] can be used as a regular GPIO.
          */
         uint32_t mode_comp:1;
         /** dref_comp : R/W; bitpos: [4:2]; default: 0;

+ 4 - 0
components/soc/esp32h2/include/soc/soc_caps.h

@@ -26,6 +26,7 @@
 
 /*-------------------------- COMMON CAPS ---------------------------------------*/
 #define SOC_ADC_SUPPORTED               1
+#define SOC_ANA_CMPR_SUPPORTED          1
 #define SOC_DEDICATED_GPIO_SUPPORTED    1
 #define SOC_UART_SUPPORTED              1
 #define SOC_GDMA_SUPPORTED              1
@@ -196,6 +197,9 @@
 #define SOC_DEDIC_GPIO_IN_CHANNELS_NUM  (8) /*!< 8 inward channels on each CPU core */
 #define SOC_DEDIC_PERIPH_ALWAYS_ENABLE  (1) /*!< The dedicated GPIO (a.k.a. fast GPIO) is featured by some customized CPU instructions, which is always enabled */
 
+/*------------------------- Analog Comparator CAPS ---------------------------*/
+#define SOC_ANA_CMPR_NUM             (1U)
+
 /*-------------------------- I2C CAPS ----------------------------------------*/
 // ESP32-H2 has 2 I2C
 #define SOC_I2C_NUM                 (2U)

+ 26 - 0
components/soc/include/soc/ana_cmpr_periph.h

@@ -0,0 +1,26 @@
+/*
+ * SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
+
+#pragma once
+
+#include <stdint.h>
+#include "soc/soc_caps.h"
+#include "soc/ana_cmpr_channel.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+typedef struct {
+    int src_gpio;
+    int ext_ref_gpio;
+} ana_cmpr_conn_t;
+
+extern const ana_cmpr_conn_t ana_cmpr_io_map[SOC_ANA_CMPR_NUM];
+
+#ifdef __cplusplus
+}
+#endif

+ 1 - 1
examples/peripherals/dac/dac_cosine_wave/main/dac_cosine_example_main.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2022-2023 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: CC0-1.0
  */