Kaynağa Gözat

dedicated gpio: add driver

morris 5 yıl önce
ebeveyn
işleme
bb1369b922

+ 1 - 0
components/driver/CMakeLists.txt

@@ -3,6 +3,7 @@ idf_build_get_property(target IDF_TARGET)
 set(srcs
     "adc_common.c"
     "dac_common.c"
+    "dedic_gpio.c"
     "gpio.c"
     "i2c.c"
     "i2s.c"

+ 405 - 0
components/driver/dedic_gpio.c

@@ -0,0 +1,405 @@
+// Copyright 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.
+// #define LOG_LOCAL_LEVEL ESP_LOG_DEBUG
+#include <stdlib.h>
+#include <string.h>
+#include <sys/lock.h>
+#include "sdkconfig.h"
+#include "esp_compiler.h"
+#include "esp_heap_caps.h"
+#include "esp_intr_alloc.h"
+#include "esp_log.h"
+#include "soc/soc_caps.h"
+#include "soc/gpio_periph.h"
+#include "soc/io_mux_reg.h"
+#include "hal/cpu_hal.h"
+#include "hal/cpu_ll.h"
+#include "driver/periph_ctrl.h"
+#include "esp_rom_gpio.h"
+#include "freertos/FreeRTOS.h"
+#if SOC_DEDICATED_GPIO_SUPPORTED
+#include "driver/dedic_gpio.h"
+#include "soc/dedic_gpio_periph.h"
+#if SOC_DEDIC_GPIO_ALLOW_REG_ACCESS
+#include "soc/dedic_gpio_struct.h"
+#include "hal/dedic_gpio_ll.h"
+#endif
+
+
+static const char *TAG = "dedic_gpio";
+
+#define DEDIC_CHECK(a, msg, tag, ret, ...)                                        \
+    do {                                                                          \
+        if (unlikely(!(a))) {                                                     \
+            ESP_LOGE(TAG, "%s(%d): " msg, __FUNCTION__, __LINE__, ##__VA_ARGS__); \
+            ret_code = ret;                                                       \
+            goto tag;                                                             \
+        }                                                                         \
+    } while (0)
+
+typedef struct dedic_gpio_platform_t dedic_gpio_platform_t;
+typedef struct dedic_gpio_bundle_t dedic_gpio_bundle_t;
+
+// Dedicated GPIO driver platform, GPIO bundles will be installed onto it
+static dedic_gpio_platform_t *s_platform[SOC_CPU_CORES_NUM];
+// platform level mutex lock
+static _lock_t s_platform_mutexlock[SOC_CPU_CORES_NUM];
+
+struct dedic_gpio_platform_t {
+    portMUX_TYPE spinlock;      // Spinlock, stop GPIO channels from accessing common resource concurrently
+    uint32_t out_occupied_mask; // mask of output channels that already occupied
+    uint32_t in_occupied_mask;  // mask of input channels that already occupied
+#if SOC_DEDIC_GPIO_HAS_INTERRUPT
+    intr_handle_t intr_hdl;     // interrupt handle
+    dedic_gpio_isr_callback_t cbs[SOC_DEDIC_GPIO_IN_CHANNELS_NUM];   // array of callback function for input channel
+    void *cb_args[SOC_DEDIC_GPIO_IN_CHANNELS_NUM];                   // array of callback arguments for input channel
+    dedic_gpio_bundle_t *in_bundles[SOC_DEDIC_GPIO_IN_CHANNELS_NUM]; // which bundle belongs to for input channel
+#endif
+#if SOC_DEDIC_GPIO_ALLOW_REG_ACCESS
+    dedic_dev_t *dev;
+#endif
+};
+
+struct dedic_gpio_bundle_t {
+    uint32_t core_id;    // CPU core ID, a GPIO bundle must be installed to a specific CPU core
+    uint32_t out_mask;   // mask of output channels in the bank
+    uint32_t in_mask;    // mask of input channels in the bank
+    uint32_t out_offset; // offset in the bank (seen from output channel)
+    uint32_t in_offset;  // offset in the bank (seen from input channel)
+    size_t nr_gpio;    // number of GPIOs in the gpio_array
+    int gpio_array[0];   // array of GPIO numbers (configured by user)
+};
+
+static esp_err_t dedic_gpio_build_platform(uint32_t core_id)
+{
+    esp_err_t ret_code = ESP_OK;
+    if (!s_platform[core_id]) {
+        // prevent building platform concurrently
+        _lock_acquire(&s_platform_mutexlock[core_id]);
+        if (!s_platform[core_id]) {
+            s_platform[core_id] = calloc(1, sizeof(dedic_gpio_platform_t));
+            if (s_platform[core_id]) {
+                // initialize platfrom members
+                s_platform[core_id]->spinlock = (portMUX_TYPE)portMUX_INITIALIZER_UNLOCKED;
+#if SOC_DEDIC_GPIO_ALLOW_REG_ACCESS
+                s_platform[core_id]->dev = &DEDIC_GPIO;
+#endif
+                periph_module_enable(dedic_gpio_periph_signals.module); // enable APB clock to peripheral
+            }
+        }
+        _lock_release(&s_platform_mutexlock[core_id]);
+
+        DEDIC_CHECK(s_platform[core_id], "no mem for s_platform[%d]", err, ESP_ERR_NO_MEM, core_id);
+        ESP_LOGD(TAG, "build platform on core[%d] at %p", core_id, s_platform);
+    }
+
+err:
+    return ret_code;
+}
+
+static void dedic_gpio_break_platform(uint32_t core_id)
+{
+    if (s_platform[core_id]) {
+        // prevent breaking platform concurrently
+        _lock_acquire(&s_platform_mutexlock[core_id]);
+        if (s_platform[core_id]) {
+            free(s_platform[core_id]);
+            s_platform[core_id] = NULL;
+            periph_module_disable(dedic_gpio_periph_signals.module); // disable module if no GPIO channel is being used
+        }
+        _lock_release(&s_platform_mutexlock[core_id]);
+    }
+}
+
+#if SOC_DEDIC_GPIO_HAS_INTERRUPT
+static void dedic_gpio_default_isr(void *arg)
+{
+    bool need_yield = false;
+    dedic_gpio_platform_t *platform = (dedic_gpio_platform_t *)arg;
+
+    // get and clear interrupt status
+    portENTER_CRITICAL_ISR(&platform->spinlock);
+    uint32_t status = dedic_gpio_ll_get_interrupt_status(platform->dev);
+    dedic_gpio_ll_clear_interrupt_status(platform->dev, status);
+    portEXIT_CRITICAL_ISR(&platform->spinlock);
+
+    // handle dedicated channel one by one
+    while (status) {
+        uint32_t channel = __builtin_ffs(status) - 1; // get dedicated channel number which triggered the interrupt
+        if (platform->cbs[channel]) {
+            if (platform->cbs[channel](platform->in_bundles[channel], channel - platform->in_bundles[channel]->in_offset, platform->cb_args[channel])) {
+                need_yield = true; // note that we need to yield at the end of isr
+            }
+        }
+        status = status & (status - 1); // clear the right most bit '1'
+    }
+
+    if (need_yield) {
+        portYIELD_FROM_ISR();
+    }
+}
+
+static esp_err_t dedic_gpio_install_interrupt(uint32_t core_id)
+{
+    esp_err_t ret_code = ESP_OK;
+    if (!s_platform[core_id]->intr_hdl) {
+        // prevent install interrupt concurrently
+        _lock_acquire(&s_platform_mutexlock[core_id]);
+        if (!s_platform[core_id]->intr_hdl) {
+            int isr_flags = 0;
+            ret_code = esp_intr_alloc(dedic_gpio_periph_signals.irq, isr_flags, dedic_gpio_default_isr, s_platform[core_id], &s_platform[core_id]->intr_hdl);
+            // clear pending interrupt
+            uint32_t status = dedic_gpio_ll_get_interrupt_status(s_platform[core_id]->dev);
+            dedic_gpio_ll_clear_interrupt_status(s_platform[core_id]->dev, status);
+        }
+        _lock_release(&s_platform_mutexlock[core_id]);
+        DEDIC_CHECK(ret_code == ESP_OK, "alloc interrupt failed", err, ret_code);
+    }
+
+err:
+    return ret_code;
+}
+
+static void dedic_gpio_uninstall_interrupt(uint32_t core_id)
+{
+    if (s_platform[core_id]->intr_hdl) {
+        // prevent uninstall interrupt concurrently
+        _lock_acquire(&s_platform_mutexlock[core_id]);
+        if (s_platform[core_id]->intr_hdl) {
+            esp_intr_free(s_platform[core_id]->intr_hdl);
+            s_platform[core_id]->intr_hdl = NULL;
+            // disable all interrupt
+            dedic_gpio_ll_enable_interrupt(s_platform[core_id]->dev, ~0UL, false);
+        }
+        _lock_release(&s_platform_mutexlock[core_id]);
+    }
+}
+
+static void dedic_gpio_set_interrupt(uint32_t core_id, uint32_t channel, dedic_gpio_intr_type_t type)
+{
+    dedic_gpio_ll_set_interrupt_type(s_platform[core_id]->dev, channel, type);
+    if (type != DEDIC_GPIO_INTR_NONE) {
+        dedic_gpio_ll_enable_interrupt(s_platform[core_id]->dev, 1 << channel, true);
+    } else {
+        dedic_gpio_ll_enable_interrupt(s_platform[core_id]->dev, 1 << channel, false);
+    }
+}
+#endif // SOC_DEDIC_GPIO_HAS_INTERRUPT
+
+esp_err_t dedic_gpio_new_bundle(const dedic_gpio_bundle_config_t *config, dedic_gpio_bundle_handle_t *ret_bundle)
+{
+    esp_err_t ret_code = ESP_OK;
+    dedic_gpio_bundle_t *bundle = NULL;
+    uint32_t out_mask = 0;
+    uint32_t in_mask = 0;
+    uint32_t core_id = cpu_hal_get_core_id(); // dedicated GPIO will be binded to the CPU who invokes this API
+
+    DEDIC_CHECK(config && ret_bundle, "invalid argument", err, ESP_ERR_INVALID_ARG);
+    DEDIC_CHECK(config->gpio_array && config->array_size > 0, "invalid GPIO array or size", err, ESP_ERR_INVALID_ARG);
+    DEDIC_CHECK(config->flags.in_en || config->flags.out_en, "no input/output mode specified", err, ESP_ERR_INVALID_ARG);
+    // lazy install s_platform[core_id]
+    DEDIC_CHECK(dedic_gpio_build_platform(core_id) == ESP_OK, "build platform %d failed", err, ESP_FAIL, core_id);
+
+    size_t bundle_size = sizeof(dedic_gpio_bundle_t) + config->array_size * sizeof(config->gpio_array[0]);
+    bundle = calloc(1, bundle_size);
+    DEDIC_CHECK(bundle, "no mem for bundle", err, ESP_ERR_NO_MEM);
+
+    // for performance reasons, we only search for continuous channels
+    uint32_t pattern = (1 << config->array_size) - 1;
+    // configure outwards channels
+    uint32_t out_offset = 0;
+    if (config->flags.out_en) {
+        DEDIC_CHECK(SOC_DEDIC_GPIO_OUT_CHANNELS_NUM >= config->array_size, "array size(%d) exceeds maximum supported out channels(%d)",
+                    err, ESP_ERR_INVALID_ARG, config->array_size, SOC_DEDIC_GPIO_OUT_CHANNELS_NUM);
+        // prevent install bundle concurrently
+        portENTER_CRITICAL(&s_platform[core_id]->spinlock);
+        for (size_t i = 0; i <= SOC_DEDIC_GPIO_OUT_CHANNELS_NUM - config->array_size; i++) {
+            if ((s_platform[core_id]->out_occupied_mask & (pattern << i)) == 0) {
+                out_mask = pattern << i;
+                out_offset = i;
+                break;
+            }
+        }
+        if (out_mask) {
+            s_platform[core_id]->out_occupied_mask |= out_mask;
+#if SOC_DEDIC_GPIO_ALLOW_REG_ACCESS
+            // always enable instruction to access output GPIO, which has better performance than register access
+            dedic_gpio_ll_enable_instruction_access_out(s_platform[core_id]->dev, out_mask, true);
+#endif
+        }
+        portEXIT_CRITICAL(&s_platform[core_id]->spinlock);
+        DEDIC_CHECK(out_mask, "no free outward channels on core[%d]", err, ESP_ERR_NOT_FOUND, core_id);
+        ESP_LOGD(TAG, "new outward bundle(%p) on core[%d], offset=%d, mask(%x)", bundle, core_id, out_offset, out_mask);
+    }
+
+    // configure inwards channels
+    uint32_t in_offset = 0;
+    if (config->flags.in_en) {
+        DEDIC_CHECK(SOC_DEDIC_GPIO_IN_CHANNELS_NUM >= config->array_size, "array size(%d) exceeds maximum supported in channels(%d)",
+                    err, ESP_ERR_INVALID_ARG, config->array_size, SOC_DEDIC_GPIO_IN_CHANNELS_NUM);
+        // prevent install bundle concurrently
+        portENTER_CRITICAL(&s_platform[core_id]->spinlock);
+        for (size_t i = 0; i <= SOC_DEDIC_GPIO_IN_CHANNELS_NUM - config->array_size; i++) {
+            if ((s_platform[core_id]->in_occupied_mask & (pattern << i)) == 0) {
+                in_mask = pattern << i;
+                in_offset = i;
+                break;
+            }
+        }
+        if (in_mask) {
+            s_platform[core_id]->in_occupied_mask |= in_mask;
+        }
+        portEXIT_CRITICAL(&s_platform[core_id]->spinlock);
+        DEDIC_CHECK(in_mask, "no free inward channels on core[%d]", err, ESP_ERR_NOT_FOUND, core_id);
+        ESP_LOGD(TAG, "new inward bundle(%p) on core[%d], offset=%d, mask(%x)", bundle, core_id, in_offset, in_mask);
+    }
+
+    // route dedicated GPIO channel signals to GPIO matrix
+    if (config->flags.in_en) {
+        for (size_t i = 0; i < config->array_size; i++) {
+            PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[config->gpio_array[i]], PIN_FUNC_GPIO);
+            esp_rom_gpio_connect_in_signal(config->gpio_array[i], dedic_gpio_periph_signals.cores[core_id].in_sig_per_channel[in_offset + i], config->flags.in_invert);
+        }
+    }
+    if (config->flags.out_en) {
+        for (size_t i = 0; i < config->array_size; i++) {
+            PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[config->gpio_array[i]], PIN_FUNC_GPIO);
+            esp_rom_gpio_connect_out_signal(config->gpio_array[i], dedic_gpio_periph_signals.cores[core_id].out_sig_per_channel[out_offset + i], config->flags.out_invert, false);
+        }
+    }
+
+    // it's safe to initialize bundle members without locks here
+    bundle->core_id = core_id;
+    bundle->out_mask = out_mask;
+    bundle->in_mask = in_mask;
+    bundle->out_offset = out_offset;
+    bundle->in_offset = in_offset;
+    bundle->nr_gpio = config->array_size;
+    memcpy(bundle->gpio_array, config->gpio_array, config->array_size * sizeof(config->gpio_array[0]));
+
+    *ret_bundle = bundle; // return bundle instance
+    return ESP_OK;
+
+err:
+    if (s_platform[core_id] && (out_mask || in_mask)) {
+        portENTER_CRITICAL(&s_platform[core_id]->spinlock);
+        s_platform[core_id]->out_occupied_mask &= ~out_mask;
+        s_platform[core_id]->in_occupied_mask &= ~in_mask;
+        portEXIT_CRITICAL(&s_platform[core_id]->spinlock);
+    }
+    if (bundle) {
+        free(bundle);
+    }
+    return ret_code;
+}
+
+esp_err_t dedic_gpio_del_bundle(dedic_gpio_bundle_handle_t bundle)
+{
+    esp_err_t ret_code = ESP_OK;
+    bool recycle_all = false;
+    DEDIC_CHECK(bundle, "invalid argument", err, ESP_ERR_INVALID_ARG);
+
+    uint32_t core_id = cpu_hal_get_core_id();
+    DEDIC_CHECK(core_id == bundle->core_id, "del bundle on wrong CPU", err, ESP_FAIL);
+
+    portENTER_CRITICAL(&s_platform[core_id]->spinlock);
+    s_platform[core_id]->out_occupied_mask &= ~(bundle->out_mask);
+    s_platform[core_id]->in_occupied_mask &= ~(bundle->in_mask);
+    if (!s_platform[core_id]->in_occupied_mask && !s_platform[core_id]->out_occupied_mask) {
+        recycle_all = true;
+    }
+    portEXIT_CRITICAL(&s_platform[core_id]->spinlock);
+
+    free(bundle);
+
+    if (recycle_all) {
+#if SOC_DEDIC_GPIO_HAS_INTERRUPT
+        dedic_gpio_uninstall_interrupt(core_id);
+#endif
+        dedic_gpio_break_platform(core_id);
+    }
+
+err:
+    return ret_code;
+}
+
+esp_err_t dedic_gpio_get_out_mask(dedic_gpio_bundle_handle_t bundle, uint32_t *mask)
+{
+    esp_err_t ret_code = ESP_OK;
+    DEDIC_CHECK(bundle && mask, "invalid argument", err, ESP_ERR_INVALID_ARG);
+    *mask = bundle->out_mask;
+err:
+    return ret_code;
+}
+
+esp_err_t dedic_gpio_get_in_mask(dedic_gpio_bundle_handle_t bundle, uint32_t *mask)
+{
+    esp_err_t ret_code = ESP_OK;
+    DEDIC_CHECK(bundle && mask, "invalid argument", err, ESP_ERR_INVALID_ARG);
+    *mask = bundle->in_mask;
+err:
+    return ret_code;
+}
+
+void dedic_gpio_bundle_write(dedic_gpio_bundle_handle_t bundle, uint32_t mask, uint32_t value)
+{
+    // For performace reasons, we don't want to check the validation of parameters here
+    // Even didn't check if we're working on the correct CPU core (i.e. bundle->core_id == current core_id)
+    cpu_ll_write_dedic_gpio_mask(bundle->out_mask & (mask << bundle->out_offset), value << bundle->out_offset);
+}
+
+uint32_t dedic_gpio_bundle_read_out(dedic_gpio_bundle_handle_t bundle)
+{
+    // For performace reasons, we don't want to check the validation of parameters here
+    // Even didn't check if we're working on the correct CPU core (i.e. bundle->core_id == current core_id)
+    uint32_t value =  cpu_ll_read_dedic_gpio_out();
+    return (value & bundle->out_mask) >> (bundle->out_offset);
+}
+
+uint32_t dedic_gpio_bundle_read_in(dedic_gpio_bundle_handle_t bundle)
+{
+    // For performace reasons, we don't want to check the validation of parameters here
+    // Even didn't check if we're working on the correct CPU core (i.e. bundle->core_id == current core_id)
+    uint32_t value  = cpu_ll_read_dedic_gpio_in();
+    return (value & bundle->in_mask) >> (bundle->in_offset);
+}
+
+#if SOC_DEDIC_GPIO_HAS_INTERRUPT
+esp_err_t dedic_gpio_bundle_set_interrupt_and_callback(dedic_gpio_bundle_handle_t bundle, uint32_t mask, dedic_gpio_intr_type_t intr_type, dedic_gpio_isr_callback_t cb_isr, void *cb_args)
+{
+    esp_err_t ret_code = ESP_OK;
+    DEDIC_CHECK(bundle, "invalid argument", err, ESP_ERR_INVALID_ARG);
+    uint32_t core_id = cpu_hal_get_core_id();
+    // lazy alloc interrupt
+    DEDIC_CHECK(dedic_gpio_install_interrupt(core_id) == ESP_OK, "allocate interrupt on core %d failed", err, ESP_FAIL, core_id);
+
+    uint32_t channel_mask = bundle->in_mask & (mask << bundle->in_offset);
+    uint32_t channel = 0;
+    while (channel_mask) {
+        channel = __builtin_ffs(channel_mask) - 1;
+        portENTER_CRITICAL(&s_platform[core_id]->spinlock);
+        dedic_gpio_set_interrupt(core_id, channel, intr_type);
+        portEXIT_CRITICAL(&s_platform[core_id]->spinlock);
+
+        s_platform[core_id]->cbs[channel] = cb_isr;
+        s_platform[core_id]->cb_args[channel] = cb_args;
+        s_platform[core_id]->in_bundles[channel] = bundle;
+        channel_mask = channel_mask & (channel_mask - 1); // clear the right most bit '1'
+    }
+
+err:
+    return ret_code;
+}
+#endif // SOC_DEDIC_GPIO_HAS_INTERRUPT
+#endif // SOC_DEDICATED_GPIO_SUPPORTED

+ 173 - 0
components/driver/include/driver/dedic_gpio.h

@@ -0,0 +1,173 @@
+// Copyright 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.
+
+#pragma once
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "esp_err.h"
+#include "esp_attr.h"
+#include "soc/soc_caps.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @brief Type of Dedicated GPIO bundle
+ */
+typedef struct dedic_gpio_bundle_t *dedic_gpio_bundle_handle_t;
+
+/**
+ * @brief Type of Dedicated GPIO bundle configuration
+ */
+typedef struct {
+    const int *gpio_array; /*!< Array of GPIO numbers, gpio_array[0] ~ gpio_array[size-1] <=> low_dedic_channel_num ~ high_dedic_channel_num */
+    size_t array_size;     /*!< Number of GPIOs in gpio_array */
+    struct {
+        int in_en: 1;      /*!< Enable input */
+        int in_invert: 1;  /*!< Invert input signal */
+        int out_en: 1;     /*!< Enable output */
+        int out_invert: 1; /*!< Invert output signal */
+    } flags; /*!< Flags to control specific behaviour of GPIO bundle */
+} dedic_gpio_bundle_config_t;
+
+/**
+ * @brief Create GPIO bundle and return the handle
+ *
+ * @param[in] config Configuration of GPIO bundle
+ * @param[out] ret_bundle Returned handle of the new created GPIO bundle
+ * @return
+ *      - ESP_OK: Create GPIO bundle successfully
+ *      - ESP_ERR_INVALID_ARG: Create GPIO bundle failed because of invalid argument
+ *      - ESP_ERR_NO_MEM: Create GPIO bundle failed because of no capable memory
+ *      - ESP_ERR_NOT_FOUND: Create GPIO bundle failed because of no enough continuous dedicated channels
+ *      - ESP_FAIL: Create GPIO bundle failed because of other error
+ *
+ * @note One has to enable at least input or output mode in "config" parameter.
+ */
+esp_err_t dedic_gpio_new_bundle(const dedic_gpio_bundle_config_t *config, dedic_gpio_bundle_handle_t *ret_bundle);
+
+/**
+ * @brief Destory GPIO bundle
+ *
+ * @param[in] bundle Handle of GPIO bundle that returned from "dedic_gpio_new_bundle"
+ * @return
+ *      - ESP_OK: Destory GPIO bundle successfully
+ *      - ESP_ERR_INVALID_ARG: Destory GPIO bundle failed because of invalid argument
+ *      - ESP_FAIL: Destory GPIO bundle failed because of other error
+ */
+esp_err_t dedic_gpio_del_bundle(dedic_gpio_bundle_handle_t bundle);
+
+/**@{*/
+/**
+ * @brief Get allocated channel mask
+ *
+ * @param[in] bundle Handle of GPIO bundle that returned from "dedic_gpio_new_bundle"
+ * @param[out] mask Returned mask value for on specific direction (in or out)
+ * @return
+ *      - ESP_OK: Get channel mask successfully
+ *      - ESP_ERR_INVALID_ARG: Get channel mask failed because of invalid argument
+ *      - ESP_FAIL: Get channel mask failed because of other error
+ *
+ * @note Each bundle should have at least one mask (in or/and out), based on bundle configuration.
+ * @note With the returned mask, user can directly invoke LL function like "cpu_ll_write_dedic_gpio_mask"
+ *       or write assembly code with dedicated GPIO instructions, to get better performance on GPIO manipulation.
+ */
+esp_err_t dedic_gpio_get_out_mask(dedic_gpio_bundle_handle_t bundle, uint32_t *mask);
+esp_err_t dedic_gpio_get_in_mask(dedic_gpio_bundle_handle_t bundle, uint32_t *mask);
+/**@}*/
+
+/**
+ * @brief Write value to GPIO bundle
+ *
+ * @param[in] bundle Handle of GPIO bundle that returned from "dedic_gpio_new_bundle"
+ * @param[in] mask Mask of the GPIOs to be written in the given bundle
+ * @param[in] value Value to write to given GPIO bundle, low bit represents low member in the bundle
+ *
+ * @note The mask is seen from the view of GPIO bundle.
+ *       For example, bundleA contains [GPIO10, GPIO12, GPIO17], to set GPIO17 individually, the mask should be 0x04.
+ * @note For performance reasons, this function doesn't check the validity of any parameters, and is placed in IRAM.
+ */
+void dedic_gpio_bundle_write(dedic_gpio_bundle_handle_t bundle, uint32_t mask, uint32_t value) IRAM_ATTR;
+
+/**
+ * @brief Read the value that output from the given GPIO bundle
+ *
+ * @param[in] bundle Handle of GPIO bundle that returned from "dedic_gpio_new_bundle"
+ * @return Value that output from the GPIO bundle, low bit represents low member in the bundle
+ *
+ * @note For performance reasons, this function doesn't check the validity of any parameters, and is placed in IRAM.
+ */
+uint32_t dedic_gpio_bundle_read_out(dedic_gpio_bundle_handle_t bundle) IRAM_ATTR;
+
+/**
+ * @brief Read the value that input to the given GPIO bundle
+ *
+ * @param[in] bundle Handle of GPIO bundle that returned from "dedic_gpio_new_bundle"
+ * @return Value that input to the GPIO bundle, low bit represents low member in the bundle
+ *
+ * @note For performance reasons, this function doesn't check the validity of any parameters, and is placed in IRAM.
+ */
+uint32_t dedic_gpio_bundle_read_in(dedic_gpio_bundle_handle_t bundle) IRAM_ATTR;
+
+#if SOC_DEDIC_GPIO_HAS_INTERRUPT
+
+/**
+ * @brief Supported type of dedicated GPIO interrupt
+ */
+typedef enum {
+    DEDIC_GPIO_INTR_NONE,          /*!< No interrupt */
+    DEDIC_GPIO_INTR_LOW_LEVEL = 2, /*!< Interrupt on low level */
+    DEDIC_GPIO_INTR_HIGH_LEVEL,    /*!< Interrupt on high level */
+    DEDIC_GPIO_INTR_NEG_EDGE,      /*!< Interrupt on negedge */
+    DEDIC_GPIO_INTR_POS_EDGE,      /*!< Interrupt on posedge */
+    DEDIC_GPIO_INTR_BOTH_EDGE      /*!< Interrupt on both negedge and posedge */
+} dedic_gpio_intr_type_t;
+
+/**
+ * @brief Type of dedicated GPIO ISR callback function
+ *
+ * @param bundle Handle of GPIO bundle that returned from "dedic_gpio_new_bundle"
+ * @param index Index of the GPIO in its corresponding bundle (count from 0)
+ * @param args User defined arguments for the callback function. It's passed through `dedic_gpio_bundle_set_interrupt_and_callback`
+ * @return If a high priority task is woken up by the callback function
+ */
+typedef bool (*dedic_gpio_isr_callback_t)(dedic_gpio_bundle_handle_t bundle, uint32_t index, void *args);
+
+/**
+ * @brief Set interrupt and callback function for GPIO bundle
+ *
+ * @param[in] bundle Handle of GPIO bundle that returned from "dedic_gpio_new_bundle"
+ * @param[in] mask Mask of the GPIOs in the given bundle
+ * @param[in] intr_type Interrupt type, set to DEDIC_GPIO_INTR_NONE can disable interrupt
+ * @param[in] cb_isr Callback function, which got invoked in ISR context. A NULL pointer here will bypass the callback
+ * @param[in] cb_args User defined argument to be passed to the callback function
+ *
+ * @note This function is only valid for bundle with input mode enabled. See "dedic_gpio_bundle_config_t"
+ * @note The mask is seen from the view of GPIO Bundle.
+ *       For example, bundleA contains [GPIO10, GPIO12, GPIO17], to set GPIO17 individually, the mask should be 0x04.
+ *
+ * @return
+ *      - ESP_OK: Set GPIO interrupt and callback function successfully
+ *      - ESP_ERR_INVALID_ARG: Set GPIO interrupt and callback function failed because of invalid argument
+ *      - ESP_FAIL: Set GPIO interrupt and callback function failed because of other error
+ */
+esp_err_t dedic_gpio_bundle_set_interrupt_and_callback(dedic_gpio_bundle_handle_t bundle, uint32_t mask, dedic_gpio_intr_type_t intr_type, dedic_gpio_isr_callback_t cb_isr, void *cb_args);
+
+#endif // SOC_DEDIC_GPIO_HAS_INTERRUPT
+
+#ifdef __cplusplus
+}
+#endif

+ 214 - 0
components/driver/test/test_dedicated_gpio.c

@@ -0,0 +1,214 @@
+#include "freertos/FreeRTOS.h"
+#include "freertos/task.h"
+#include "freertos/semphr.h"
+#include "unity.h"
+#include "test_utils.h"
+#include "esp_rom_sys.h"
+#include "soc/soc_caps.h"
+#include "hal/cpu_ll.h"
+#include "driver/gpio.h"
+#if SOC_DEDICATED_GPIO_SUPPORTED
+#include "driver/dedic_gpio.h"
+
+TEST_CASE("Dedicated GPIO bundle install/uninstall", "[dedic_gpio]")
+{
+    const int test_gpios[SOC_DEDIC_GPIO_OUT_CHANNELS_NUM / 2] = {0};
+    const int test2_gpios[SOC_DEDIC_GPIO_OUT_CHANNELS_NUM / 2 + 1] = {0};
+    const int test3_gpios[SOC_DEDIC_GPIO_OUT_CHANNELS_NUM + 1] = {0};
+    dedic_gpio_bundle_handle_t test_bundle, test_bundle2, test_bundle3 = NULL;
+    dedic_gpio_bundle_config_t bundle_config = {
+        .gpio_array = test_gpios,
+        .array_size = sizeof(test_gpios) / sizeof(test_gpios[0]),
+    };
+    dedic_gpio_bundle_config_t bundle_config2 = {
+        .gpio_array = test2_gpios,
+        .array_size = sizeof(test2_gpios) / sizeof(test2_gpios[0]),
+        .flags = {
+            .out_en = 1,
+        },
+    };
+    dedic_gpio_bundle_config_t bundle_config3 = {
+        .gpio_array = test3_gpios,
+        .array_size = sizeof(test3_gpios) / sizeof(test3_gpios[0]),
+        .flags = {
+            .out_en = 1,
+        },
+    };
+
+    TEST_ASSERT_EQUAL_MESSAGE(ESP_ERR_INVALID_ARG, dedic_gpio_new_bundle(&bundle_config, &test_bundle), "shouldn't create bundle if no mode is specified");
+
+    bundle_config.flags.out_en = 1;
+    TEST_ASSERT_EQUAL_MESSAGE(ESP_OK, dedic_gpio_new_bundle(&bundle_config, &test_bundle), "create bundle with half channels failed");
+    uint32_t mask = 0;
+    TEST_ESP_OK(dedic_gpio_get_out_mask(test_bundle, &mask));
+    TEST_ASSERT_EQUAL_MESSAGE((1 << (SOC_DEDIC_GPIO_OUT_CHANNELS_NUM / 2)) - 1, mask, "wrong out mask");
+    TEST_ESP_OK(dedic_gpio_get_in_mask(test_bundle, &mask));
+    TEST_ASSERT_EQUAL_MESSAGE(0, mask, "wrong in mask");
+
+    TEST_ASSERT_EQUAL_MESSAGE(ESP_ERR_NOT_FOUND, dedic_gpio_new_bundle(&bundle_config2, &test_bundle2), "shouldn't create bundle if there's no enough channels");
+    TEST_ASSERT_EQUAL_MESSAGE(ESP_OK, dedic_gpio_del_bundle(test_bundle), "delete bundle failed");
+
+    TEST_ASSERT_EQUAL_MESSAGE(ESP_ERR_INVALID_ARG, dedic_gpio_new_bundle(&bundle_config3, &test_bundle3), "shouldn't create bundle if the array size exceeds maximum");
+}
+
+#define TEST_GPIO_GROUP_SIZE (4)
+
+typedef struct {
+    SemaphoreHandle_t sem;
+    const int gpios[TEST_GPIO_GROUP_SIZE];
+} test_dedic_task_context_t;
+
+static void test_dedic_gpio_on_specific_core(void *args)
+{
+    test_dedic_task_context_t *ctx = (test_dedic_task_context_t *)args;
+    uint32_t value = 0;
+    cpu_ll_write_dedic_gpio_all(0x0); // clear all out channels
+
+    // configure a group of GPIOs, output only
+    const int bundleA_gpios[] = {ctx->gpios[0], ctx->gpios[1]};
+    gpio_config_t io_conf = {
+        .mode = GPIO_MODE_OUTPUT,
+    };
+    for (int i = 0; i < sizeof(bundleA_gpios) / sizeof(bundleA_gpios[0]); i++) {
+        io_conf.pin_bit_mask = 1ULL << bundleA_gpios[i];
+        gpio_config(&io_conf);
+    }
+    // Create bundleA, output only
+    dedic_gpio_bundle_handle_t bundleA = NULL;
+    dedic_gpio_bundle_config_t bundleA_config = {
+        .gpio_array = bundleA_gpios,
+        .array_size = sizeof(bundleA_gpios) / sizeof(bundleA_gpios[0]),
+        .flags = {
+            .out_en = 1,
+        },
+    };
+    TEST_ESP_OK(dedic_gpio_new_bundle(&bundleA_config, &bundleA));
+
+    // configure another group of GPIOs, input and output
+    const int bundleB_gpios[] = {ctx->gpios[2], ctx->gpios[3]};
+    io_conf.mode = GPIO_MODE_INPUT_OUTPUT;
+    for (int i = 0; i < sizeof(bundleB_gpios) / sizeof(bundleB_gpios[0]); i++) {
+        io_conf.pin_bit_mask = 1ULL << bundleB_gpios[i];
+        gpio_config(&io_conf);
+    }
+
+    // GPIO bundleB, input and output
+    dedic_gpio_bundle_handle_t bundleB = NULL;
+    dedic_gpio_bundle_config_t bundleB_config = {
+        .gpio_array = bundleB_gpios,
+        .array_size = sizeof(bundleB_gpios) / sizeof(bundleB_gpios[0]),
+        .flags = {
+            .in_en = 1,
+            .out_en = 1,
+        },
+    };
+    TEST_ESP_OK(dedic_gpio_new_bundle(&bundleB_config, &bundleB));
+
+    dedic_gpio_bundle_write(bundleA, 0x01, 0x01);
+    dedic_gpio_bundle_write(bundleB, 0x03, 0x03);
+
+    value = cpu_ll_read_dedic_gpio_out();
+    TEST_ASSERT_EQUAL(0x0D, value); // 1101
+    value = cpu_ll_read_dedic_gpio_in();
+    TEST_ASSERT_EQUAL(0x03, value); // 11
+
+    dedic_gpio_bundle_write(bundleB, 0x02, 0x0);
+    value = cpu_ll_read_dedic_gpio_out();
+    TEST_ASSERT_EQUAL(0x05, value); // 0101
+    value = cpu_ll_read_dedic_gpio_in();
+    TEST_ASSERT_EQUAL(0x01, value); // 01
+
+    cpu_ll_write_dedic_gpio_all(0x0F); // Set all out channels
+    value = cpu_ll_read_dedic_gpio_out();
+    TEST_ASSERT_EQUAL(0x0F, value);
+    value = cpu_ll_read_dedic_gpio_in();
+    TEST_ASSERT_EQUAL(0x03, value);                               // 11
+    TEST_ASSERT_EQUAL(0x03, dedic_gpio_bundle_read_out(bundleA)); // 11
+    TEST_ASSERT_EQUAL(0x00, dedic_gpio_bundle_read_in(bundleA));  // input is not enabled for bundleA
+    TEST_ASSERT_EQUAL(0x03, dedic_gpio_bundle_read_out(bundleB)); // 11
+    TEST_ASSERT_EQUAL(0x03, dedic_gpio_bundle_read_in(bundleB));  // 11
+
+    TEST_ESP_OK(dedic_gpio_del_bundle(bundleA));
+    TEST_ESP_OK(dedic_gpio_del_bundle(bundleB));
+
+    xSemaphoreGive(ctx->sem);
+    vTaskDelete(NULL);
+}
+
+TEST_CASE("Dedicated GPIO run on multiple CPU core", "[dedic_gpio]")
+{
+    SemaphoreHandle_t sem = xSemaphoreCreateCounting(SOC_CPU_CORES_NUM, 0);
+
+    for (int i = 0; i < SOC_CPU_CORES_NUM; i++) {
+        int start_gpio = i * TEST_GPIO_GROUP_SIZE;
+        test_dedic_task_context_t isr_ctx = {
+            .sem = sem,
+            .gpios = {start_gpio, start_gpio + 1, start_gpio + 2, start_gpio + 3}
+        };
+        xTaskCreatePinnedToCore(test_dedic_gpio_on_specific_core, "dedic_gpio_test_tsk", 4096, &isr_ctx, 1, NULL, i);
+    }
+
+    for (int i = 0; i < SOC_CPU_CORES_NUM; i++) {
+        xSemaphoreTake(sem, pdMS_TO_TICKS(1000));
+    }
+    vSemaphoreDelete(sem);
+}
+
+IRAM_ATTR static void test_dedic_gpio_isr_callback(void *args)
+{
+    SemaphoreHandle_t sem = (SemaphoreHandle_t)args;
+    BaseType_t high_task_wakeup = pdFALSE;
+    esp_rom_printf("GPIO event\r\n");
+    xSemaphoreGiveFromISR(sem, &high_task_wakeup);
+    if (high_task_wakeup) {
+        esp_rom_printf("high priority task wake up\r\n");
+    }
+}
+
+TEST_CASE("Dedicated GPIO interrupt and callback", "[dedic_gpio]")
+{
+    SemaphoreHandle_t sem = xSemaphoreCreateBinary();
+
+    // configure GPIO
+    const int bundle_gpios[] = {0, 1};
+    gpio_config_t io_conf = {
+        .mode = GPIO_MODE_INPUT_OUTPUT,
+    };
+    for (int i = 0; i < sizeof(bundle_gpios) / sizeof(bundle_gpios[0]); i++) {
+        io_conf.pin_bit_mask = 1ULL << bundle_gpios[i];
+        gpio_config(&io_conf);
+    }
+    dedic_gpio_bundle_handle_t bundle = NULL;
+    dedic_gpio_bundle_config_t bundle_config = {
+        .gpio_array = bundle_gpios,
+        .array_size = sizeof(bundle_gpios) / sizeof(bundle_gpios[0]),
+        .flags = {
+            .in_en = 1,
+            .out_en = 1,
+        },
+    };
+    TEST_ESP_OK(dedic_gpio_new_bundle(&bundle_config, &bundle));
+
+    // enable interrupt on GPIO1
+    TEST_ESP_OK(gpio_set_intr_type(1, GPIO_INTR_POSEDGE));
+    // install gpio isr service
+    TEST_ESP_OK(gpio_install_isr_service(0));
+    // hook isr handler for specific gpio pin
+    TEST_ESP_OK(gpio_isr_handler_add(1, test_dedic_gpio_isr_callback, sem));
+
+    // trigger a posedge on GPIO1
+    dedic_gpio_bundle_write(bundle, BIT(1), 0x00);
+    dedic_gpio_bundle_write(bundle, BIT(1), 0xFF);
+    // wait for done semaphore
+    TEST_ASSERT_EQUAL(pdTRUE, xSemaphoreTake(sem, pdMS_TO_TICKS(1000)));
+
+    // remove isr handler for gpio number
+    TEST_ESP_OK(gpio_isr_handler_remove(1));
+    // uninstall GPIO interrupt service
+    gpio_uninstall_isr_service();
+
+    TEST_ESP_OK(dedic_gpio_del_bundle(bundle));
+    vSemaphoreDelete(sem);
+}
+
+#endif // #if SOC_DEDICATED_GPIO_SUPPORTED

+ 1 - 0
components/esp32s2/ld/esp32s2.peripherals.ld

@@ -26,5 +26,6 @@ PROVIDE ( SYSCON = 0x3f426000 );
 PROVIDE ( I2C1 = 0x3f427000 );
 PROVIDE ( TWAI = 0x3f42B000 );
 PROVIDE ( APB_SARADC = 0x3f440000 );
+PROVIDE ( DEDIC_GPIO = 0x3f4cf000 );
 PROVIDE ( USB0     = 0x60080000 );
 PROVIDE ( USB_WRAP = 0x3f439000 );

+ 8 - 0
components/hal/esp32s2/include/hal/clk_gate_ll.h

@@ -84,6 +84,8 @@ static inline uint32_t periph_ll_get_clk_en_mask(periph_module_t periph)
         return DPORT_WIFI_CLK_WIFI_BT_COMMON_M;
     case PERIPH_SYSTIMER_MODULE:
         return DPORT_SYSTIMER_CLK_EN;
+    case PERIPH_DEDIC_GPIO_MODULE:
+        return DPORT_CLK_EN_DEDICATED_GPIO;
     case PERIPH_AES_MODULE:
         return DPORT_CRYPTO_AES_CLK_EN;
     case PERIPH_SHA_MODULE:
@@ -156,6 +158,8 @@ static inline uint32_t periph_ll_get_rst_en_mask(periph_module_t periph, bool en
         return DPORT_TWAI_RST;
     case PERIPH_SYSTIMER_MODULE:
         return DPORT_SYSTIMER_RST;
+    case PERIPH_DEDIC_GPIO_MODULE:
+        return DPORT_RST_EN_DEDICATED_GPIO;
     case PERIPH_AES_MODULE:
         if (enable == true) {
             // Clear reset on digital signature, otherwise AES unit is held in reset also.
@@ -207,6 +211,8 @@ static inline uint32_t periph_ll_get_rst_en_mask(periph_module_t periph, bool en
 static inline uint32_t periph_ll_get_clk_en_reg(periph_module_t periph)
 {
     switch (periph) {
+    case PERIPH_DEDIC_GPIO_MODULE:
+        return DPORT_CPU_PERI_CLK_EN_REG;
     case PERIPH_RNG_MODULE:
     case PERIPH_WIFI_MODULE:
     case PERIPH_WIFI_BT_COMMON_MODULE:
@@ -226,6 +232,8 @@ static inline uint32_t periph_ll_get_clk_en_reg(periph_module_t periph)
 static inline uint32_t periph_ll_get_rst_en_reg(periph_module_t periph)
 {
     switch (periph) {
+    case PERIPH_DEDIC_GPIO_MODULE:
+        return DPORT_CPU_PERI_RST_EN_REG;
     case PERIPH_RNG_MODULE:
     case PERIPH_WIFI_MODULE:
     case PERIPH_WIFI_BT_COMMON_MODULE:

+ 25 - 1
components/hal/esp32s2/include/hal/cpu_ll.h

@@ -154,7 +154,7 @@ static inline bool cpu_ll_is_debugger_attached(void)
     uint32_t dcr = 0;
     uint32_t reg = DSRSET;
     RER(reg, dcr);
-    return (dcr&0x1);
+    return (dcr & 0x1);
 }
 
 
@@ -168,6 +168,30 @@ static inline void cpu_ll_set_vecbase(const void* vecbase)
     asm volatile ("wsr %0, vecbase" :: "r" (vecbase));
 }
 
+static inline uint32_t cpu_ll_read_dedic_gpio_in(void)
+{
+    uint32_t value = 0;
+    asm volatile("get_gpio_in %0" : "=r"(value) : :);
+    return value;
+}
+
+static inline uint32_t cpu_ll_read_dedic_gpio_out(void)
+{
+    uint32_t value = 0;
+    asm volatile("rur.gpio_out %0" : "=r"(value) : :);
+    return value;
+}
+
+static inline void cpu_ll_write_dedic_gpio_all(uint32_t value)
+{
+    asm volatile("wur.gpio_out %0"::"r"(value):);
+}
+
+static inline void cpu_ll_write_dedic_gpio_mask(uint32_t mask, uint32_t value)
+{
+    asm volatile("wr_mask_gpio_out %0, %1" : : "r"(value), "r"(mask):);
+}
+
 #ifdef __cplusplus
 }
 #endif

+ 110 - 0
components/hal/esp32s2/include/hal/dedic_gpio_ll.h

@@ -0,0 +1,110 @@
+// Copyright 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.
+#pragma once
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "soc/dedic_gpio_struct.h"
+
+static inline void dedic_gpio_ll_enable_instruction_access_out(dedic_dev_t *dev, uint32_t channel_mask, bool enable)
+{
+    if (enable) {
+        dev->gpio_out_cpu.val |= channel_mask;
+    } else {
+        dev->gpio_out_cpu.val &= ~channel_mask;
+    }
+}
+
+static inline void dedic_gpio_ll_write_all(dedic_dev_t *dev, uint32_t value)
+{
+    dev->gpio_out_drt.val = value;
+}
+
+static inline void dedic_gpio_ll_write_mask(dedic_dev_t *dev, uint32_t channel_mask, uint32_t value)
+{
+    dedic_gpio_out_msk_reg_t d = {
+        .gpio_out_msk = channel_mask,
+        .gpio_out_value = value
+    };
+    dev->gpio_out_msk.val = d.val;
+}
+
+static inline void dedic_gpio_ll_set_channel(dedic_dev_t *dev, uint32_t channel)
+{
+    dev->gpio_out_idv.val = 1 << (2 * channel);
+}
+
+static inline void dedic_gpio_ll_clear_channel(dedic_dev_t *dev, uint32_t channel)
+{
+    dev->gpio_out_idv.val = 2 << (2 * channel);
+}
+
+static inline void dedic_gpio_ll_toggle_channel(dedic_dev_t *dev, uint32_t channel)
+{
+    dev->gpio_out_idv.val = 3 << (2 * channel);
+}
+
+static inline uint32_t dedic_gpio_ll_read_out_all(dedic_dev_t *dev)
+{
+    return dev->gpio_out_scan.gpio_out_status;
+}
+
+static inline uint32_t dedic_gpio_ll_read_in_all(dedic_dev_t *dev)
+{
+    return dev->gpio_in_scan.gpio_in_status;
+}
+
+static inline void dedic_gpio_ll_set_input_delay(dedic_dev_t *dev, uint32_t channel, uint32_t delay_cpu_clks)
+{
+    dev->gpio_in_dly.val &= ~(3 << (2 * channel));
+    dev->gpio_in_dly.val |= (delay_cpu_clks & 0x03) << (2 * channel);
+}
+
+static inline uint32_t dedic_gpio_ll_get_input_delay(dedic_dev_t *dev, uint32_t channel)
+{
+    return (dev->gpio_in_dly.val & (3 << (2 * channel)) >> (2 * channel));
+}
+
+static inline void dedic_gpio_ll_set_interrupt_type(dedic_dev_t *dev, uint32_t channel, uint32_t type)
+{
+    dev->gpio_intr_rcgn.val &= ~(7 << (3 * channel));
+    dev->gpio_intr_rcgn.val |= (type & 0x07) << (3 * channel);
+}
+
+static inline void dedic_gpio_ll_enable_interrupt(dedic_dev_t *dev, uint32_t channel_mask, bool enable)
+{
+    if (enable) {
+        dev->gpio_intr_rls.val |= channel_mask;
+    } else {
+        dev->gpio_intr_rls.val &= ~channel_mask;
+    }
+}
+
+static inline uint32_t __attribute__((always_inline)) dedic_gpio_ll_get_interrupt_status(dedic_dev_t *dev)
+{
+    return dev->gpio_intr_st.val;
+}
+
+static inline void __attribute__((always_inline)) dedic_gpio_ll_clear_interrupt_status(dedic_dev_t *dev, uint32_t channel_mask)
+{
+    dev->gpio_intr_clr.val = channel_mask;
+}
+
+#ifdef __cplusplus
+}
+#endif

+ 8 - 0
components/hal/esp32s3/include/hal/clk_gate_ll.h

@@ -92,6 +92,8 @@ static inline uint32_t periph_ll_get_clk_en_mask(periph_module_t periph)
         return SYSTEM_BT_LC_EN;
     case PERIPH_SYSTIMER_MODULE:
         return SYSTEM_SYSTIMER_CLK_EN;
+    case PERIPH_DEDIC_GPIO_MODULE:
+        return SYSTEM_CLK_EN_DEDICATED_GPIO;
     case PERIPH_GDMA_MODULE:
         return SYSTEM_DMA_CLK_EN;
     case PERIPH_AES_MODULE:
@@ -163,6 +165,8 @@ static inline uint32_t periph_ll_get_rst_en_mask(periph_module_t periph, bool en
         return SYSTEM_TWAI_RST;
     case PERIPH_SYSTIMER_MODULE:
         return SYSTEM_SYSTIMER_RST;
+    case PERIPH_DEDIC_GPIO_MODULE:
+        return SYSTEM_RST_EN_DEDICATED_GPIO;
     case PERIPH_GDMA_MODULE:
         return SYSTEM_DMA_RST;
     case PERIPH_AES_MODULE:
@@ -197,6 +201,8 @@ static inline uint32_t periph_ll_get_rst_en_mask(periph_module_t periph, bool en
 static uint32_t periph_ll_get_clk_en_reg(periph_module_t periph)
 {
     switch (periph) {
+    case PERIPH_DEDIC_GPIO_MODULE:
+        return SYSTEM_CPU_PERI_CLK_EN_REG;
     case PERIPH_RNG_MODULE:
     case PERIPH_WIFI_MODULE:
     case PERIPH_BT_MODULE:
@@ -219,6 +225,8 @@ static uint32_t periph_ll_get_clk_en_reg(periph_module_t periph)
 static uint32_t periph_ll_get_rst_en_reg(periph_module_t periph)
 {
     switch (periph) {
+    case PERIPH_DEDIC_GPIO_MODULE:
+        return SYSTEM_CPU_PERI_RST_EN_REG;
     case PERIPH_RNG_MODULE:
     case PERIPH_WIFI_MODULE:
     case PERIPH_BT_MODULE:

+ 39 - 10
components/hal/esp32s3/include/hal/cpu_ll.h

@@ -44,7 +44,7 @@ static inline uint32_t cpu_ll_get_cycle_count(void)
     return result;
 }
 
-static inline void* cpu_ll_get_sp(void)
+static inline void *cpu_ll_get_sp(void)
 {
     void *sp;
     asm volatile ("mov %0, sp;" : "=r" (sp));
@@ -94,21 +94,21 @@ static inline void cpu_ll_clear_breakpoint(int id)
     WSR(IBREAKENABLE, en);
 }
 
-static inline uint32_t cpu_ll_ptr_to_pc(const void* addr)
+static inline uint32_t cpu_ll_ptr_to_pc(const void *addr)
 {
     return ((uint32_t) addr);
 }
 
-static inline void* cpu_ll_pc_to_ptr(uint32_t pc)
+static inline void *cpu_ll_pc_to_ptr(uint32_t pc)
 {
-    return (void*) ((pc & 0x3fffffff) | 0x40000000);
+    return (void *) ((pc & 0x3fffffff) | 0x40000000);
 }
 
 static inline void cpu_ll_set_watchpoint(int id,
-                                        const void* addr,
-                                        size_t size,
-                                        bool on_read,
-                                        bool on_write)
+        const void *addr,
+        size_t size,
+        bool on_read,
+        bool on_write)
 {
     uint32_t dbreakc = 0x3F;
 
@@ -158,7 +158,7 @@ static inline bool cpu_ll_is_debugger_attached(void)
     uint32_t dcr = 0;
     uint32_t reg = DSRSET;
     RER(reg, dcr);
-    return (dcr&0x1);
+    return (dcr & 0x1);
 }
 
 static inline void cpu_ll_break(void)
@@ -166,11 +166,40 @@ static inline void cpu_ll_break(void)
     __asm__ ("break 0,0");
 }
 
-static inline void cpu_ll_set_vecbase(const void* vecbase)
+static inline void cpu_ll_set_vecbase(const void *vecbase)
 {
     asm volatile ("wsr %0, vecbase" :: "r" (vecbase));
 }
 
+static inline uint32_t cpu_ll_read_dedic_gpio_in(void)
+{
+    uint32_t value = 0;
+    asm volatile("get_gpio_in %0" : "=r"(value) : :);
+    return value;
+}
+
+static inline uint32_t cpu_ll_read_dedic_gpio_out(void)
+{
+    uint32_t value = 0;
+    asm volatile("rur.gpio_out %0" : "=r"(value) : :);
+    return value;
+}
+
+static inline void cpu_ll_write_dedic_gpio_all(uint32_t value)
+{
+    asm volatile("wur.gpio_out %0"::"r"(value):);
+}
+
+static inline void cpu_ll_write_dedic_gpio_mask(uint32_t mask, uint32_t value)
+{
+    // ToDo: check if ESP32-S3 supports mask write instruction
+    uint32_t orig = 0;
+    asm volatile("rur.gpio_out %0" : "=r"(orig) : :);
+    orig &= ~mask;
+    orig |= value & mask;
+    asm volatile("wur.gpio_out %0"::"r"(orig):);
+}
+
 #ifdef __cplusplus
 }
 #endif

+ 1 - 0
components/soc/soc/esp32s2/CMakeLists.txt

@@ -1,6 +1,7 @@
 add_library(soc_esp32s2 STATIC
     "adc_periph.c"
     "dac_periph.c"
+    "dedic_gpio_periph.c"
     "gpio_periph.c"
     "pcnt_periph.c"
     "rtc_io_periph.c"

+ 45 - 0
components/soc/soc/esp32s2/dedic_gpio_periph.c

@@ -0,0 +1,45 @@
+// Copyright 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.
+
+#include "soc/dedic_gpio_periph.h"
+#include "soc/gpio_sig_map.h"
+
+const dedic_gpio_signal_conn_t dedic_gpio_periph_signals = {
+    .module = PERIPH_DEDIC_GPIO_MODULE,
+    .irq = ETS_DEDICATED_GPIO_INTR_SOURCE,
+    .cores = {
+        [0] = {
+            .in_sig_per_channel = {
+                [0] = PRO_ALONEGPIO_IN0_IDX,
+                [1] = PRO_ALONEGPIO_IN1_IDX,
+                [2] = PRO_ALONEGPIO_IN2_IDX,
+                [3] = PRO_ALONEGPIO_IN3_IDX,
+                [4] = PRO_ALONEGPIO_IN4_IDX,
+                [5] = PRO_ALONEGPIO_IN5_IDX,
+                [6] = PRO_ALONEGPIO_IN6_IDX,
+                [7] = PRO_ALONEGPIO_IN7_IDX,
+            },
+            .out_sig_per_channel = {
+                [0] = PRO_ALONEGPIO_OUT0_IDX,
+                [1] = PRO_ALONEGPIO_OUT1_IDX,
+                [2] = PRO_ALONEGPIO_OUT2_IDX,
+                [3] = PRO_ALONEGPIO_OUT3_IDX,
+                [4] = PRO_ALONEGPIO_OUT4_IDX,
+                [5] = PRO_ALONEGPIO_OUT5_IDX,
+                [6] = PRO_ALONEGPIO_OUT6_IDX,
+                [7] = PRO_ALONEGPIO_OUT7_IDX,
+            }
+        },
+    },
+};

+ 751 - 0
components/soc/soc/esp32s2/include/soc/dedic_gpio_reg.h

@@ -0,0 +1,751 @@
+/** Copyright 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.
+ */
+
+#pragma once
+
+#include <stdint.h>
+#include "soc/soc.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+/** Configuration registers */
+
+/** DEDIC_GPIO_OUT_DRT_REG register
+ *  Dedicated GPIO Directive Output
+ *  register
+ */
+#define DEDIC_GPIO_OUT_DRT_REG (DR_REG_DEDICATED_GPIO_BASE + 0x0)
+/* DEDIC_GPIO_OUT_DRT_VLAUE : WO; bitpos: [8:0]; default: 0;
+ * This register is used to configure directive output value of 8-channel
+ * dedicated
+ * gpio.
+ */
+#define DEDIC_GPIO_OUT_DRT_VLAUE    0x000000FF
+#define DEDIC_GPIO_OUT_DRT_VLAUE_M  (DEDIC_GPIO_OUT_DRT_VLAUE_V << DEDIC_GPIO_OUT_DRT_VLAUE_S)
+#define DEDIC_GPIO_OUT_DRT_VLAUE_V  0x000000FF
+#define DEDIC_GPIO_OUT_DRT_VLAUE_S  0
+
+/** DEDIC_GPIO_OUT_MSK_REG register
+ *  Dedicated GPIO Mask Output
+ *  register
+ */
+#define DEDIC_GPIO_OUT_MSK_REG (DR_REG_DEDICATED_GPIO_BASE + 0x4)
+/* DEDIC_GPIO_OUT_VALUE : WO; bitpos: [8:0]; default: 0;
+ * This register is used to configure masked output value of 8-channel
+ * dedicated
+ * gpio.
+ */
+#define DEDIC_GPIO_OUT_VALUE    0x000000FF
+#define DEDIC_GPIO_OUT_VALUE_M  (DEDIC_GPIO_OUT_VALUE_V << DEDIC_GPIO_OUT_VALUE_S)
+#define DEDIC_GPIO_OUT_VALUE_V  0x000000FF
+#define DEDIC_GPIO_OUT_VALUE_S  0
+/* DEDIC_GPIO_OUT_MSK : WO; bitpos: [16:8]; default: 0;
+ * This register is used to configure channels which would be masked. 1:
+ * corresponding channel's output would be
+ * masked.
+ */
+#define DEDIC_GPIO_OUT_MSK    0x000000FF
+#define DEDIC_GPIO_OUT_MSK_M  (DEDIC_GPIO_OUT_MSK_V << DEDIC_GPIO_OUT_MSK_S)
+#define DEDIC_GPIO_OUT_MSK_V  0x000000FF
+#define DEDIC_GPIO_OUT_MSK_S  8
+
+/** DEDIC_GPIO_OUT_IDV_REG register
+ *  Dedicated GPIO Individual Output
+ *  register
+ */
+#define DEDIC_GPIO_OUT_IDV_REG (DR_REG_DEDICATED_GPIO_BASE + 0x8)
+/* DEDIC_GPIO_OUT_IDV_CH0 : WO; bitpos: [2:0]; default: 0;
+ * Configure channel 0 output value. 0: hold output value; 1: set output
+ * value; 2: clear output value; 3: inverse output
+ * value.
+ */
+#define DEDIC_GPIO_OUT_IDV_CH0    0x00000003
+#define DEDIC_GPIO_OUT_IDV_CH0_M  (DEDIC_GPIO_OUT_IDV_CH0_V << DEDIC_GPIO_OUT_IDV_CH0_S)
+#define DEDIC_GPIO_OUT_IDV_CH0_V  0x00000003
+#define DEDIC_GPIO_OUT_IDV_CH0_S  0
+/* DEDIC_GPIO_OUT_IDV_CH1 : WO; bitpos: [4:2]; default: 0;
+ * Configure channel 1 output value. 0: hold output value; 1: set output
+ * value; 2: clear output value; 3: inverse output
+ * value.
+ */
+#define DEDIC_GPIO_OUT_IDV_CH1    0x00000003
+#define DEDIC_GPIO_OUT_IDV_CH1_M  (DEDIC_GPIO_OUT_IDV_CH1_V << DEDIC_GPIO_OUT_IDV_CH1_S)
+#define DEDIC_GPIO_OUT_IDV_CH1_V  0x00000003
+#define DEDIC_GPIO_OUT_IDV_CH1_S  2
+/* DEDIC_GPIO_OUT_IDV_CH2 : WO; bitpos: [6:4]; default: 0;
+ * Configure channel 2 output value. 0: hold output value; 1: set output
+ * value; 2: clear output value; 3: inverse output
+ * value.
+ */
+#define DEDIC_GPIO_OUT_IDV_CH2    0x00000003
+#define DEDIC_GPIO_OUT_IDV_CH2_M  (DEDIC_GPIO_OUT_IDV_CH2_V << DEDIC_GPIO_OUT_IDV_CH2_S)
+#define DEDIC_GPIO_OUT_IDV_CH2_V  0x00000003
+#define DEDIC_GPIO_OUT_IDV_CH2_S  4
+/* DEDIC_GPIO_OUT_IDV_CH3 : WO; bitpos: [8:6]; default: 0;
+ * Configure channel 3 output value. 0: hold output value; 1: set output
+ * value; 2: clear output value; 3: inverse output
+ * value.
+ */
+#define DEDIC_GPIO_OUT_IDV_CH3    0x00000003
+#define DEDIC_GPIO_OUT_IDV_CH3_M  (DEDIC_GPIO_OUT_IDV_CH3_V << DEDIC_GPIO_OUT_IDV_CH3_S)
+#define DEDIC_GPIO_OUT_IDV_CH3_V  0x00000003
+#define DEDIC_GPIO_OUT_IDV_CH3_S  6
+/* DEDIC_GPIO_OUT_IDV_CH4 : WO; bitpos: [10:8]; default: 0;
+ * Configure channel 4 output value. 0: hold output value; 1: set output
+ * value; 2: clear output value; 3: inverse output
+ * value.
+ */
+#define DEDIC_GPIO_OUT_IDV_CH4    0x00000003
+#define DEDIC_GPIO_OUT_IDV_CH4_M  (DEDIC_GPIO_OUT_IDV_CH4_V << DEDIC_GPIO_OUT_IDV_CH4_S)
+#define DEDIC_GPIO_OUT_IDV_CH4_V  0x00000003
+#define DEDIC_GPIO_OUT_IDV_CH4_S  8
+/* DEDIC_GPIO_OUT_IDV_CH5 : WO; bitpos: [12:10]; default: 0;
+ * Configure channel 5 output value. 0: hold output value; 1: set output
+ * value; 2: clear output value; 3: inverse output
+ * value.
+ */
+#define DEDIC_GPIO_OUT_IDV_CH5    0x00000003
+#define DEDIC_GPIO_OUT_IDV_CH5_M  (DEDIC_GPIO_OUT_IDV_CH5_V << DEDIC_GPIO_OUT_IDV_CH5_S)
+#define DEDIC_GPIO_OUT_IDV_CH5_V  0x00000003
+#define DEDIC_GPIO_OUT_IDV_CH5_S  10
+/* DEDIC_GPIO_OUT_IDV_CH6 : WO; bitpos: [14:12]; default: 0;
+ * Configure channel 6 output value. 0: hold output value; 1: set output
+ * value; 2: clear output value; 3: inverse output
+ * value.
+ */
+#define DEDIC_GPIO_OUT_IDV_CH6    0x00000003
+#define DEDIC_GPIO_OUT_IDV_CH6_M  (DEDIC_GPIO_OUT_IDV_CH6_V << DEDIC_GPIO_OUT_IDV_CH6_S)
+#define DEDIC_GPIO_OUT_IDV_CH6_V  0x00000003
+#define DEDIC_GPIO_OUT_IDV_CH6_S  12
+/* DEDIC_GPIO_OUT_IDV_CH7 : WO; bitpos: [16:14]; default: 0;
+ * Configure channel 7 output value. 0: hold output value; 1: set output
+ * value; 2: clear output value; 3: inverse output
+ * value.
+ */
+#define DEDIC_GPIO_OUT_IDV_CH7    0x00000003
+#define DEDIC_GPIO_OUT_IDV_CH7_M  (DEDIC_GPIO_OUT_IDV_CH7_V << DEDIC_GPIO_OUT_IDV_CH7_S)
+#define DEDIC_GPIO_OUT_IDV_CH7_V  0x00000003
+#define DEDIC_GPIO_OUT_IDV_CH7_S  14
+
+/** DEDIC_GPIO_OUT_CPU_REG register
+ *  Dedicated GPIO Output Mode Select
+ *  register
+ */
+#define DEDIC_GPIO_OUT_CPU_REG (DR_REG_DEDICATED_GPIO_BASE + 0x10)
+/* DEDIC_GPIO_OUT_CPU_SEL0 : R/W; bitpos: [0]; default: 0;
+ * Select gpio out value configured by registers or CPU instructors for
+ * channel 0. 1: select CPU
+ * instructors.
+ */
+#define DEDIC_GPIO_OUT_CPU_SEL0    (BIT(0))
+#define DEDIC_GPIO_OUT_CPU_SEL0_M  (DEDIC_GPIO_OUT_CPU_SEL0_V << DEDIC_GPIO_OUT_CPU_SEL0_S)
+#define DEDIC_GPIO_OUT_CPU_SEL0_V  0x00000001
+#define DEDIC_GPIO_OUT_CPU_SEL0_S  0
+/* DEDIC_GPIO_OUT_CPU_SEL1 : R/W; bitpos: [1]; default: 0;
+ * Select gpio out value configured by registers or CPU instructors for
+ * channel 1. 1: select CPU
+ * instructors.
+ */
+#define DEDIC_GPIO_OUT_CPU_SEL1    (BIT(1))
+#define DEDIC_GPIO_OUT_CPU_SEL1_M  (DEDIC_GPIO_OUT_CPU_SEL1_V << DEDIC_GPIO_OUT_CPU_SEL1_S)
+#define DEDIC_GPIO_OUT_CPU_SEL1_V  0x00000001
+#define DEDIC_GPIO_OUT_CPU_SEL1_S  1
+/* DEDIC_GPIO_OUT_CPU_SEL2 : R/W; bitpos: [2]; default: 0;
+ * Select gpio out value configured by registers or CPU instructors for
+ * channel 2. 1: select CPU
+ * instructors.
+ */
+#define DEDIC_GPIO_OUT_CPU_SEL2    (BIT(2))
+#define DEDIC_GPIO_OUT_CPU_SEL2_M  (DEDIC_GPIO_OUT_CPU_SEL2_V << DEDIC_GPIO_OUT_CPU_SEL2_S)
+#define DEDIC_GPIO_OUT_CPU_SEL2_V  0x00000001
+#define DEDIC_GPIO_OUT_CPU_SEL2_S  2
+/* DEDIC_GPIO_OUT_CPU_SEL3 : R/W; bitpos: [3]; default: 0;
+ * Select gpio out value configured by registers or CPU instructors for
+ * channel 3. 1: select CPU
+ * instructors.
+ */
+#define DEDIC_GPIO_OUT_CPU_SEL3    (BIT(3))
+#define DEDIC_GPIO_OUT_CPU_SEL3_M  (DEDIC_GPIO_OUT_CPU_SEL3_V << DEDIC_GPIO_OUT_CPU_SEL3_S)
+#define DEDIC_GPIO_OUT_CPU_SEL3_V  0x00000001
+#define DEDIC_GPIO_OUT_CPU_SEL3_S  3
+/* DEDIC_GPIO_OUT_CPU_SEL4 : R/W; bitpos: [4]; default: 0;
+ * Select gpio out value configured by registers or CPU instructors for
+ * channel 4. 1: select CPU
+ * instructors.
+ */
+#define DEDIC_GPIO_OUT_CPU_SEL4    (BIT(4))
+#define DEDIC_GPIO_OUT_CPU_SEL4_M  (DEDIC_GPIO_OUT_CPU_SEL4_V << DEDIC_GPIO_OUT_CPU_SEL4_S)
+#define DEDIC_GPIO_OUT_CPU_SEL4_V  0x00000001
+#define DEDIC_GPIO_OUT_CPU_SEL4_S  4
+/* DEDIC_GPIO_OUT_CPU_SEL5 : R/W; bitpos: [5]; default: 0;
+ * Select gpio out value configured by registers or CPU instructors for
+ * channel 5. 1: select CPU
+ * instructors.
+ */
+#define DEDIC_GPIO_OUT_CPU_SEL5    (BIT(5))
+#define DEDIC_GPIO_OUT_CPU_SEL5_M  (DEDIC_GPIO_OUT_CPU_SEL5_V << DEDIC_GPIO_OUT_CPU_SEL5_S)
+#define DEDIC_GPIO_OUT_CPU_SEL5_V  0x00000001
+#define DEDIC_GPIO_OUT_CPU_SEL5_S  5
+/* DEDIC_GPIO_OUT_CPU_SEL6 : R/W; bitpos: [6]; default: 0;
+ * Select gpio out value configured by registers or CPU instructors for
+ * channel 6. 1: select CPU
+ * instructors.
+ */
+#define DEDIC_GPIO_OUT_CPU_SEL6    (BIT(6))
+#define DEDIC_GPIO_OUT_CPU_SEL6_M  (DEDIC_GPIO_OUT_CPU_SEL6_V << DEDIC_GPIO_OUT_CPU_SEL6_S)
+#define DEDIC_GPIO_OUT_CPU_SEL6_V  0x00000001
+#define DEDIC_GPIO_OUT_CPU_SEL6_S  6
+/* DEDIC_GPIO_OUT_CPU_SEL7 : R/W; bitpos: [7]; default: 0;
+ * Select gpio out value configured by registers or CPU instructors for
+ * channel 7. 1: select CPU
+ * instructors.
+ */
+#define DEDIC_GPIO_OUT_CPU_SEL7    (BIT(7))
+#define DEDIC_GPIO_OUT_CPU_SEL7_M  (DEDIC_GPIO_OUT_CPU_SEL7_V << DEDIC_GPIO_OUT_CPU_SEL7_S)
+#define DEDIC_GPIO_OUT_CPU_SEL7_V  0x00000001
+#define DEDIC_GPIO_OUT_CPU_SEL7_S  7
+
+/** DEDIC_GPIO_IN_DLY_REG register
+ *  Dedicated GPIO Input Delay Configuration
+ *  register
+ */
+#define DEDIC_GPIO_IN_DLY_REG (DR_REG_DEDICATED_GPIO_BASE + 0x14)
+/* DEDIC_GPIO_IN_DLY_CH0 : R/W; bitpos: [2:0]; default: 0;
+ * Configure gpio 0 input delay. 0: No delay; 1: one clock delay; 2: two
+ * clock delay; 3: three clock
+ * delay.
+ */
+#define DEDIC_GPIO_IN_DLY_CH0    0x00000003
+#define DEDIC_GPIO_IN_DLY_CH0_M  (DEDIC_GPIO_IN_DLY_CH0_V << DEDIC_GPIO_IN_DLY_CH0_S)
+#define DEDIC_GPIO_IN_DLY_CH0_V  0x00000003
+#define DEDIC_GPIO_IN_DLY_CH0_S  0
+/* DEDIC_GPIO_IN_DLY_CH1 : R/W; bitpos: [4:2]; default: 0;
+ * Configure gpio 1 input delay. 0: No delay; 1: one clock delay; 2: two
+ * clock delay; 3: three clock
+ * delay.
+ */
+#define DEDIC_GPIO_IN_DLY_CH1    0x00000003
+#define DEDIC_GPIO_IN_DLY_CH1_M  (DEDIC_GPIO_IN_DLY_CH1_V << DEDIC_GPIO_IN_DLY_CH1_S)
+#define DEDIC_GPIO_IN_DLY_CH1_V  0x00000003
+#define DEDIC_GPIO_IN_DLY_CH1_S  2
+/* DEDIC_GPIO_IN_DLY_CH2 : R/W; bitpos: [6:4]; default: 0;
+ * Configure gpio 2 input delay. 0: No delay; 1: one clock delay; 2: two
+ * clock delay; 3: three clock
+ * delay.
+ */
+#define DEDIC_GPIO_IN_DLY_CH2    0x00000003
+#define DEDIC_GPIO_IN_DLY_CH2_M  (DEDIC_GPIO_IN_DLY_CH2_V << DEDIC_GPIO_IN_DLY_CH2_S)
+#define DEDIC_GPIO_IN_DLY_CH2_V  0x00000003
+#define DEDIC_GPIO_IN_DLY_CH2_S  4
+/* DEDIC_GPIO_IN_DLY_CH3 : R/W; bitpos: [8:6]; default: 0;
+ * Configure gpio 3 input delay. 0: No delay; 1: one clock delay; 2: two
+ * clock delay; 3: three clock
+ * delay.
+ */
+#define DEDIC_GPIO_IN_DLY_CH3    0x00000003
+#define DEDIC_GPIO_IN_DLY_CH3_M  (DEDIC_GPIO_IN_DLY_CH3_V << DEDIC_GPIO_IN_DLY_CH3_S)
+#define DEDIC_GPIO_IN_DLY_CH3_V  0x00000003
+#define DEDIC_GPIO_IN_DLY_CH3_S  6
+/* DEDIC_GPIO_IN_DLY_CH4 : R/W; bitpos: [10:8]; default: 0;
+ * Configure gpio 4 input delay. 0: No delay; 1: one clock delay; 2: two
+ * clock delay; 3: three clock
+ * delay.
+ */
+#define DEDIC_GPIO_IN_DLY_CH4    0x00000003
+#define DEDIC_GPIO_IN_DLY_CH4_M  (DEDIC_GPIO_IN_DLY_CH4_V << DEDIC_GPIO_IN_DLY_CH4_S)
+#define DEDIC_GPIO_IN_DLY_CH4_V  0x00000003
+#define DEDIC_GPIO_IN_DLY_CH4_S  8
+/* DEDIC_GPIO_IN_DLY_CH5 : R/W; bitpos: [12:10]; default: 0;
+ * Configure gpio 5 input delay. 0: No delay; 1: one clock delay; 2: two
+ * clock delay; 3: three clock
+ * delay.
+ */
+#define DEDIC_GPIO_IN_DLY_CH5    0x00000003
+#define DEDIC_GPIO_IN_DLY_CH5_M  (DEDIC_GPIO_IN_DLY_CH5_V << DEDIC_GPIO_IN_DLY_CH5_S)
+#define DEDIC_GPIO_IN_DLY_CH5_V  0x00000003
+#define DEDIC_GPIO_IN_DLY_CH5_S  10
+/* DEDIC_GPIO_IN_DLY_CH6 : R/W; bitpos: [14:12]; default: 0;
+ * Configure gpio 6 input delay. 0: No delay; 1: one clock delay; 2: two
+ * clock delay; 3: three clock
+ * delay.
+ */
+#define DEDIC_GPIO_IN_DLY_CH6    0x00000003
+#define DEDIC_GPIO_IN_DLY_CH6_M  (DEDIC_GPIO_IN_DLY_CH6_V << DEDIC_GPIO_IN_DLY_CH6_S)
+#define DEDIC_GPIO_IN_DLY_CH6_V  0x00000003
+#define DEDIC_GPIO_IN_DLY_CH6_S  12
+/* DEDIC_GPIO_IN_DLY_CH7 : R/W; bitpos: [16:14]; default: 0;
+ * Configure gpio 7 input delay. 0: No delay; 1: one clock delay; 2: two
+ * clock delay; 3: three clock
+ * delay.
+ */
+#define DEDIC_GPIO_IN_DLY_CH7    0x00000003
+#define DEDIC_GPIO_IN_DLY_CH7_M  (DEDIC_GPIO_IN_DLY_CH7_V << DEDIC_GPIO_IN_DLY_CH7_S)
+#define DEDIC_GPIO_IN_DLY_CH7_V  0x00000003
+#define DEDIC_GPIO_IN_DLY_CH7_S  14
+
+/** DEDIC_GPIO_INTR_RCGN_REG register
+ *  Dedicated GPIO Interrupts Generate Mode
+ *  register
+ */
+#define DEDIC_GPIO_INTR_RCGN_REG (DR_REG_DEDICATED_GPIO_BASE + 0x1c)
+/* DEDIC_GPIO_INTR_MODE_CH0 : R/W; bitpos: [3:0]; default: 0;
+ * Configure channel 0 interrupt generate mode.
+ * 0/1: do not generate interrupt;
+ * 2: low level trigger;
+ * 3: high level trigger;
+ * 4: falling edge trigger;
+ * 5: raising edge trigger;
+ * 6/7: falling and raising edge
+ * trigger.
+ */
+#define DEDIC_GPIO_INTR_MODE_CH0    0x00000007
+#define DEDIC_GPIO_INTR_MODE_CH0_M  (DEDIC_GPIO_INTR_MODE_CH0_V << DEDIC_GPIO_INTR_MODE_CH0_S)
+#define DEDIC_GPIO_INTR_MODE_CH0_V  0x00000007
+#define DEDIC_GPIO_INTR_MODE_CH0_S  0
+/* DEDIC_GPIO_INTR_MODE_CH1 : R/W; bitpos: [6:3]; default: 0;
+ * Configure channel 1 interrupt generate mode.
+ * 0/1: do not generate interrupt;
+ * 2: low level trigger;
+ * 3: high level trigger;
+ * 4: falling edge trigger;
+ * 5: raising edge trigger;
+ * 6/7: falling and raising edge
+ * trigger.
+ */
+#define DEDIC_GPIO_INTR_MODE_CH1    0x00000007
+#define DEDIC_GPIO_INTR_MODE_CH1_M  (DEDIC_GPIO_INTR_MODE_CH1_V << DEDIC_GPIO_INTR_MODE_CH1_S)
+#define DEDIC_GPIO_INTR_MODE_CH1_V  0x00000007
+#define DEDIC_GPIO_INTR_MODE_CH1_S  3
+/* DEDIC_GPIO_INTR_MODE_CH2 : R/W; bitpos: [9:6]; default: 0;
+ * Configure channel 2 interrupt generate mode.
+ * 0/1: do not generate interrupt;
+ * 2: low level trigger;
+ * 3: high level trigger;
+ * 4: falling edge trigger;
+ * 5: raising edge trigger;
+ * 6/7: falling and raising edge
+ * trigger.
+ */
+#define DEDIC_GPIO_INTR_MODE_CH2    0x00000007
+#define DEDIC_GPIO_INTR_MODE_CH2_M  (DEDIC_GPIO_INTR_MODE_CH2_V << DEDIC_GPIO_INTR_MODE_CH2_S)
+#define DEDIC_GPIO_INTR_MODE_CH2_V  0x00000007
+#define DEDIC_GPIO_INTR_MODE_CH2_S  6
+/* DEDIC_GPIO_INTR_MODE_CH3 : R/W; bitpos: [12:9]; default: 0;
+ * Configure channel 3 interrupt generate mode.
+ * 0/1: do not generate interrupt;
+ * 2: low level trigger;
+ * 3: high level trigger;
+ * 4: falling edge trigger;
+ * 5: raising edge trigger;
+ * 6/7: falling and raising edge
+ * trigger.
+ */
+#define DEDIC_GPIO_INTR_MODE_CH3    0x00000007
+#define DEDIC_GPIO_INTR_MODE_CH3_M  (DEDIC_GPIO_INTR_MODE_CH3_V << DEDIC_GPIO_INTR_MODE_CH3_S)
+#define DEDIC_GPIO_INTR_MODE_CH3_V  0x00000007
+#define DEDIC_GPIO_INTR_MODE_CH3_S  9
+/* DEDIC_GPIO_INTR_MODE_CH4 : R/W; bitpos: [15:12]; default: 0;
+ * Configure channel 4 interrupt generate mode.
+ * 0/1: do not generate interrupt;
+ * 2: low level trigger;
+ * 3: high level trigger;
+ * 4: falling edge trigger;
+ * 5: raising edge trigger;
+ * 6/7: falling and raising edge
+ * trigger.
+ */
+#define DEDIC_GPIO_INTR_MODE_CH4    0x00000007
+#define DEDIC_GPIO_INTR_MODE_CH4_M  (DEDIC_GPIO_INTR_MODE_CH4_V << DEDIC_GPIO_INTR_MODE_CH4_S)
+#define DEDIC_GPIO_INTR_MODE_CH4_V  0x00000007
+#define DEDIC_GPIO_INTR_MODE_CH4_S  12
+/* DEDIC_GPIO_INTR_MODE_CH5 : R/W; bitpos: [18:15]; default: 0;
+ * Configure channel 5 interrupt generate mode.
+ * 0/1: do not generate interrupt;
+ * 2: low level trigger;
+ * 3: high level trigger;
+ * 4: falling edge trigger;
+ * 5: raising edge trigger;
+ * 6/7: falling and raising edge
+ * trigger.
+ */
+#define DEDIC_GPIO_INTR_MODE_CH5    0x00000007
+#define DEDIC_GPIO_INTR_MODE_CH5_M  (DEDIC_GPIO_INTR_MODE_CH5_V << DEDIC_GPIO_INTR_MODE_CH5_S)
+#define DEDIC_GPIO_INTR_MODE_CH5_V  0x00000007
+#define DEDIC_GPIO_INTR_MODE_CH5_S  15
+/* DEDIC_GPIO_INTR_MODE_CH6 : R/W; bitpos: [21:18]; default: 0;
+ * Configure channel 6 interrupt generate mode.
+ * 0/1: do not generate interrupt;
+ * 2: low level trigger;
+ * 3: high level trigger;
+ * 4: falling edge trigger;
+ * 5: raising edge trigger;
+ * 6/7: falling and raising edge
+ * trigger.
+ */
+#define DEDIC_GPIO_INTR_MODE_CH6    0x00000007
+#define DEDIC_GPIO_INTR_MODE_CH6_M  (DEDIC_GPIO_INTR_MODE_CH6_V << DEDIC_GPIO_INTR_MODE_CH6_S)
+#define DEDIC_GPIO_INTR_MODE_CH6_V  0x00000007
+#define DEDIC_GPIO_INTR_MODE_CH6_S  18
+/* DEDIC_GPIO_INTR_MODE_CH7 : R/W; bitpos: [24:21]; default: 0;
+ * Configure channel 7 interrupt generate mode.
+ * 0/1: do not generate interrupt;
+ * 2: low level trigger;
+ * 3: high level trigger;
+ * 4: falling edge trigger;
+ * 5: raising edge trigger;
+ * 6/7: falling and raising edge
+ * trigger.
+ */
+#define DEDIC_GPIO_INTR_MODE_CH7    0x00000007
+#define DEDIC_GPIO_INTR_MODE_CH7_M  (DEDIC_GPIO_INTR_MODE_CH7_V << DEDIC_GPIO_INTR_MODE_CH7_S)
+#define DEDIC_GPIO_INTR_MODE_CH7_V  0x00000007
+#define DEDIC_GPIO_INTR_MODE_CH7_S  21
+
+
+/** Status registers */
+
+/** DEDIC_GPIO_OUT_SCAN_REG register
+ *  Dedicated GPIO Output Status
+ *  register
+ */
+#define DEDIC_GPIO_OUT_SCAN_REG (DR_REG_DEDICATED_GPIO_BASE + 0xc)
+/* DEDIC_GPIO_OUT_STATUS : RO; bitpos: [8:0]; default: 0;
+ * gpio out value configured by DEDIC_GPIO_OUT_DRT_REG,
+ * DEDIC_GPIO_OUT_MSK_REG,
+ * DEDIC_GPIO_OUT_IDV_REG.
+ */
+#define DEDIC_GPIO_OUT_STATUS    0x000000FF
+#define DEDIC_GPIO_OUT_STATUS_M  (DEDIC_GPIO_OUT_STATUS_V << DEDIC_GPIO_OUT_STATUS_S)
+#define DEDIC_GPIO_OUT_STATUS_V  0x000000FF
+#define DEDIC_GPIO_OUT_STATUS_S  0
+
+/** DEDIC_GPIO_IN_SCAN_REG register
+ *  Dedicated GPIO Input Status
+ *  register
+ */
+#define DEDIC_GPIO_IN_SCAN_REG (DR_REG_DEDICATED_GPIO_BASE + 0x18)
+/* DEDIC_GPIO_IN_STATUS : RO; bitpos: [8:0]; default: 0;
+ * gpio in value after configured by
+ * DEDIC_GPIO_IN_DLY_REG.
+ */
+#define DEDIC_GPIO_IN_STATUS    0x000000FF
+#define DEDIC_GPIO_IN_STATUS_M  (DEDIC_GPIO_IN_STATUS_V << DEDIC_GPIO_IN_STATUS_S)
+#define DEDIC_GPIO_IN_STATUS_V  0x000000FF
+#define DEDIC_GPIO_IN_STATUS_S  0
+
+
+/** Interrupt registers */
+
+/** DEDIC_GPIO_INTR_RAW_REG register
+ *  Raw interrupt
+ *  status
+ */
+#define DEDIC_GPIO_INTR_RAW_REG (DR_REG_DEDICATED_GPIO_BASE + 0x20)
+/* DEDIC_GPIO0_INT_RAW : RO; bitpos: [0]; default: 0;
+ * This interrupt raw bit turns to high level when dedicated GPIO 0 has
+ * level/edge change configured by
+ * DEDIC_GPIO_INTR_RCGN_REG.
+ */
+#define DEDIC_GPIO0_INT_RAW    (BIT(0))
+#define DEDIC_GPIO0_INT_RAW_M  (DEDIC_GPIO0_INT_RAW_V << DEDIC_GPIO0_INT_RAW_S)
+#define DEDIC_GPIO0_INT_RAW_V  0x00000001
+#define DEDIC_GPIO0_INT_RAW_S  0
+/* DEDIC_GPIO1_INT_RAW : RO; bitpos: [1]; default: 0;
+ * This interrupt raw bit turns to high level when dedicated GPIO 1 has
+ * level/edge change configured by
+ * DEDIC_GPIO_INTR_RCGN_REG.
+ */
+#define DEDIC_GPIO1_INT_RAW    (BIT(1))
+#define DEDIC_GPIO1_INT_RAW_M  (DEDIC_GPIO1_INT_RAW_V << DEDIC_GPIO1_INT_RAW_S)
+#define DEDIC_GPIO1_INT_RAW_V  0x00000001
+#define DEDIC_GPIO1_INT_RAW_S  1
+/* DEDIC_GPIO2_INT_RAW : RO; bitpos: [2]; default: 0;
+ * This interrupt raw bit turns to high level when dedicated GPIO 2 has
+ * level/edge change configured by
+ * DEDIC_GPIO_INTR_RCGN_REG.
+ */
+#define DEDIC_GPIO2_INT_RAW    (BIT(2))
+#define DEDIC_GPIO2_INT_RAW_M  (DEDIC_GPIO2_INT_RAW_V << DEDIC_GPIO2_INT_RAW_S)
+#define DEDIC_GPIO2_INT_RAW_V  0x00000001
+#define DEDIC_GPIO2_INT_RAW_S  2
+/* DEDIC_GPIO3_INT_RAW : RO; bitpos: [3]; default: 0;
+ * This interrupt raw bit turns to high level when dedicated GPIO 3 has
+ * level/edge change configured by
+ * DEDIC_GPIO_INTR_RCGN_REG.
+ */
+#define DEDIC_GPIO3_INT_RAW    (BIT(3))
+#define DEDIC_GPIO3_INT_RAW_M  (DEDIC_GPIO3_INT_RAW_V << DEDIC_GPIO3_INT_RAW_S)
+#define DEDIC_GPIO3_INT_RAW_V  0x00000001
+#define DEDIC_GPIO3_INT_RAW_S  3
+/* DEDIC_GPIO4_INT_RAW : RO; bitpos: [4]; default: 0;
+ * This interrupt raw bit turns to high level when dedicated GPIO 4 has
+ * level/edge change configured by
+ * DEDIC_GPIO_INTR_RCGN_REG.
+ */
+#define DEDIC_GPIO4_INT_RAW    (BIT(4))
+#define DEDIC_GPIO4_INT_RAW_M  (DEDIC_GPIO4_INT_RAW_V << DEDIC_GPIO4_INT_RAW_S)
+#define DEDIC_GPIO4_INT_RAW_V  0x00000001
+#define DEDIC_GPIO4_INT_RAW_S  4
+/* DEDIC_GPIO5_INT_RAW : RO; bitpos: [5]; default: 0;
+ * This interrupt raw bit turns to high level when dedicated GPIO 5 has
+ * level/edge change configured by
+ * DEDIC_GPIO_INTR_RCGN_REG.
+ */
+#define DEDIC_GPIO5_INT_RAW    (BIT(5))
+#define DEDIC_GPIO5_INT_RAW_M  (DEDIC_GPIO5_INT_RAW_V << DEDIC_GPIO5_INT_RAW_S)
+#define DEDIC_GPIO5_INT_RAW_V  0x00000001
+#define DEDIC_GPIO5_INT_RAW_S  5
+/* DEDIC_GPIO6_INT_RAW : RO; bitpos: [6]; default: 0;
+ * This interrupt raw bit turns to high level when dedicated GPIO 6 has
+ * level/edge change configured by
+ * DEDIC_GPIO_INTR_RCGN_REG.
+ */
+#define DEDIC_GPIO6_INT_RAW    (BIT(6))
+#define DEDIC_GPIO6_INT_RAW_M  (DEDIC_GPIO6_INT_RAW_V << DEDIC_GPIO6_INT_RAW_S)
+#define DEDIC_GPIO6_INT_RAW_V  0x00000001
+#define DEDIC_GPIO6_INT_RAW_S  6
+/* DEDIC_GPIO7_INT_RAW : RO; bitpos: [7]; default: 0;
+ * This interrupt raw bit turns to high level when dedicated GPIO 7 has
+ * level/edge change configured by
+ * DEDIC_GPIO_INTR_RCGN_REG.
+ */
+#define DEDIC_GPIO7_INT_RAW    (BIT(7))
+#define DEDIC_GPIO7_INT_RAW_M  (DEDIC_GPIO7_INT_RAW_V << DEDIC_GPIO7_INT_RAW_S)
+#define DEDIC_GPIO7_INT_RAW_V  0x00000001
+#define DEDIC_GPIO7_INT_RAW_S  7
+
+/** DEDIC_GPIO_INTR_RLS_REG register
+ *  Interrupt enable
+ *  bits
+ */
+#define DEDIC_GPIO_INTR_RLS_REG (DR_REG_DEDICATED_GPIO_BASE + 0x24)
+/* DEDIC_GPIO0_INT_ENA : R/W; bitpos: [0]; default: 0;
+ * This enable bit for reg_gpio0_int_st
+ * register.
+ */
+#define DEDIC_GPIO0_INT_ENA    (BIT(0))
+#define DEDIC_GPIO0_INT_ENA_M  (DEDIC_GPIO0_INT_ENA_V << DEDIC_GPIO0_INT_ENA_S)
+#define DEDIC_GPIO0_INT_ENA_V  0x00000001
+#define DEDIC_GPIO0_INT_ENA_S  0
+/* DEDIC_GPIO1_INT_ENA : R/W; bitpos: [1]; default: 0;
+ * This enable bit for reg_gpio1_int_st
+ * register.
+ */
+#define DEDIC_GPIO1_INT_ENA    (BIT(1))
+#define DEDIC_GPIO1_INT_ENA_M  (DEDIC_GPIO1_INT_ENA_V << DEDIC_GPIO1_INT_ENA_S)
+#define DEDIC_GPIO1_INT_ENA_V  0x00000001
+#define DEDIC_GPIO1_INT_ENA_S  1
+/* DEDIC_GPIO2_INT_ENA : R/W; bitpos: [2]; default: 0;
+ * This enable bit for reg_gpio2_int_st
+ * register.
+ */
+#define DEDIC_GPIO2_INT_ENA    (BIT(2))
+#define DEDIC_GPIO2_INT_ENA_M  (DEDIC_GPIO2_INT_ENA_V << DEDIC_GPIO2_INT_ENA_S)
+#define DEDIC_GPIO2_INT_ENA_V  0x00000001
+#define DEDIC_GPIO2_INT_ENA_S  2
+/* DEDIC_GPIO3_INT_ENA : R/W; bitpos: [3]; default: 0;
+ * This enable bit for reg_gpio3_int_st
+ * register.
+ */
+#define DEDIC_GPIO3_INT_ENA    (BIT(3))
+#define DEDIC_GPIO3_INT_ENA_M  (DEDIC_GPIO3_INT_ENA_V << DEDIC_GPIO3_INT_ENA_S)
+#define DEDIC_GPIO3_INT_ENA_V  0x00000001
+#define DEDIC_GPIO3_INT_ENA_S  3
+/* DEDIC_GPIO4_INT_ENA : R/W; bitpos: [4]; default: 0;
+ * This enable bit for reg_gpio4_int_st
+ * register.
+ */
+#define DEDIC_GPIO4_INT_ENA    (BIT(4))
+#define DEDIC_GPIO4_INT_ENA_M  (DEDIC_GPIO4_INT_ENA_V << DEDIC_GPIO4_INT_ENA_S)
+#define DEDIC_GPIO4_INT_ENA_V  0x00000001
+#define DEDIC_GPIO4_INT_ENA_S  4
+/* DEDIC_GPIO5_INT_ENA : R/W; bitpos: [5]; default: 0;
+ * This enable bit for reg_gpio5_int_st
+ * register.
+ */
+#define DEDIC_GPIO5_INT_ENA    (BIT(5))
+#define DEDIC_GPIO5_INT_ENA_M  (DEDIC_GPIO5_INT_ENA_V << DEDIC_GPIO5_INT_ENA_S)
+#define DEDIC_GPIO5_INT_ENA_V  0x00000001
+#define DEDIC_GPIO5_INT_ENA_S  5
+/* DEDIC_GPIO6_INT_ENA : R/W; bitpos: [6]; default: 0;
+ * This enable bit for reg_gpio6_int_st
+ * register.
+ */
+#define DEDIC_GPIO6_INT_ENA    (BIT(6))
+#define DEDIC_GPIO6_INT_ENA_M  (DEDIC_GPIO6_INT_ENA_V << DEDIC_GPIO6_INT_ENA_S)
+#define DEDIC_GPIO6_INT_ENA_V  0x00000001
+#define DEDIC_GPIO6_INT_ENA_S  6
+/* DEDIC_GPIO7_INT_ENA : R/W; bitpos: [7]; default: 0;
+ * This enable bit for reg_gpio7_int_st
+ * register.
+ */
+#define DEDIC_GPIO7_INT_ENA    (BIT(7))
+#define DEDIC_GPIO7_INT_ENA_M  (DEDIC_GPIO7_INT_ENA_V << DEDIC_GPIO7_INT_ENA_S)
+#define DEDIC_GPIO7_INT_ENA_V  0x00000001
+#define DEDIC_GPIO7_INT_ENA_S  7
+
+/** DEDIC_GPIO_INTR_ST_REG register
+ *  Masked interrupt
+ *  status
+ */
+#define DEDIC_GPIO_INTR_ST_REG (DR_REG_DEDICATED_GPIO_BASE + 0x28)
+/* DEDIC_GPIO0_INT_ST : RO; bitpos: [0]; default: 0;
+ * This is the status bit for reg_gpio0_int_raw when reg_gpio0_int_ena is
+ * set to
+ * 1.
+ */
+#define DEDIC_GPIO0_INT_ST    (BIT(0))
+#define DEDIC_GPIO0_INT_ST_M  (DEDIC_GPIO0_INT_ST_V << DEDIC_GPIO0_INT_ST_S)
+#define DEDIC_GPIO0_INT_ST_V  0x00000001
+#define DEDIC_GPIO0_INT_ST_S  0
+/* DEDIC_GPIO1_INT_ST : RO; bitpos: [1]; default: 0;
+ * This is the status bit for reg_gpio1_int_raw when reg_gpio1_int_ena is
+ * set to
+ * 1.
+ */
+#define DEDIC_GPIO1_INT_ST    (BIT(1))
+#define DEDIC_GPIO1_INT_ST_M  (DEDIC_GPIO1_INT_ST_V << DEDIC_GPIO1_INT_ST_S)
+#define DEDIC_GPIO1_INT_ST_V  0x00000001
+#define DEDIC_GPIO1_INT_ST_S  1
+/* DEDIC_GPIO2_INT_ST : RO; bitpos: [2]; default: 0;
+ * This is the status bit for reg_gpio2_int_raw when reg_gpio2_int_ena is
+ * set to
+ * 1.
+ */
+#define DEDIC_GPIO2_INT_ST    (BIT(2))
+#define DEDIC_GPIO2_INT_ST_M  (DEDIC_GPIO2_INT_ST_V << DEDIC_GPIO2_INT_ST_S)
+#define DEDIC_GPIO2_INT_ST_V  0x00000001
+#define DEDIC_GPIO2_INT_ST_S  2
+/* DEDIC_GPIO3_INT_ST : RO; bitpos: [3]; default: 0;
+ * This is the status bit for reg_gpio3_int_raw when reg_gpio3_int_ena is
+ * set to
+ * 1.
+ */
+#define DEDIC_GPIO3_INT_ST    (BIT(3))
+#define DEDIC_GPIO3_INT_ST_M  (DEDIC_GPIO3_INT_ST_V << DEDIC_GPIO3_INT_ST_S)
+#define DEDIC_GPIO3_INT_ST_V  0x00000001
+#define DEDIC_GPIO3_INT_ST_S  3
+/* DEDIC_GPIO4_INT_ST : RO; bitpos: [4]; default: 0;
+ * This is the status bit for reg_gpio4_int_raw when reg_gpio4_int_ena is
+ * set to
+ * 1.
+ */
+#define DEDIC_GPIO4_INT_ST    (BIT(4))
+#define DEDIC_GPIO4_INT_ST_M  (DEDIC_GPIO4_INT_ST_V << DEDIC_GPIO4_INT_ST_S)
+#define DEDIC_GPIO4_INT_ST_V  0x00000001
+#define DEDIC_GPIO4_INT_ST_S  4
+/* DEDIC_GPIO5_INT_ST : RO; bitpos: [5]; default: 0;
+ * This is the status bit for reg_gpio5_int_raw when reg_gpio5_int_ena is
+ * set to
+ * 1.
+ */
+#define DEDIC_GPIO5_INT_ST    (BIT(5))
+#define DEDIC_GPIO5_INT_ST_M  (DEDIC_GPIO5_INT_ST_V << DEDIC_GPIO5_INT_ST_S)
+#define DEDIC_GPIO5_INT_ST_V  0x00000001
+#define DEDIC_GPIO5_INT_ST_S  5
+/* DEDIC_GPIO6_INT_ST : RO; bitpos: [6]; default: 0;
+ * This is the status bit for reg_gpio6_int_raw when reg_gpio6_int_ena is
+ * set to
+ * 1.
+ */
+#define DEDIC_GPIO6_INT_ST    (BIT(6))
+#define DEDIC_GPIO6_INT_ST_M  (DEDIC_GPIO6_INT_ST_V << DEDIC_GPIO6_INT_ST_S)
+#define DEDIC_GPIO6_INT_ST_V  0x00000001
+#define DEDIC_GPIO6_INT_ST_S  6
+/* DEDIC_GPIO7_INT_ST : RO; bitpos: [7]; default: 0;
+ * This is the status bit for reg_gpio7_int_raw when reg_gpio7_int_ena is
+ * set to
+ * 1.
+ */
+#define DEDIC_GPIO7_INT_ST    (BIT(7))
+#define DEDIC_GPIO7_INT_ST_M  (DEDIC_GPIO7_INT_ST_V << DEDIC_GPIO7_INT_ST_S)
+#define DEDIC_GPIO7_INT_ST_V  0x00000001
+#define DEDIC_GPIO7_INT_ST_S  7
+
+/** DEDIC_GPIO_INTR_CLR_REG register
+ *  Interrupt clear
+ *  bits
+ */
+#define DEDIC_GPIO_INTR_CLR_REG (DR_REG_DEDICATED_GPIO_BASE + 0x2c)
+/* DEDIC_GPIO0_INT_CLR : WO; bitpos: [0]; default: 0;
+ * Set this bit to clear the reg_gpio0_int_raw
+ * interrupt.
+ */
+#define DEDIC_GPIO0_INT_CLR    (BIT(0))
+#define DEDIC_GPIO0_INT_CLR_M  (DEDIC_GPIO0_INT_CLR_V << DEDIC_GPIO0_INT_CLR_S)
+#define DEDIC_GPIO0_INT_CLR_V  0x00000001
+#define DEDIC_GPIO0_INT_CLR_S  0
+/* DEDIC_GPIO1_INT_CLR : WO; bitpos: [1]; default: 0;
+ * Set this bit to clear the reg_gpio1_int_raw
+ * interrupt.
+ */
+#define DEDIC_GPIO1_INT_CLR    (BIT(1))
+#define DEDIC_GPIO1_INT_CLR_M  (DEDIC_GPIO1_INT_CLR_V << DEDIC_GPIO1_INT_CLR_S)
+#define DEDIC_GPIO1_INT_CLR_V  0x00000001
+#define DEDIC_GPIO1_INT_CLR_S  1
+/* DEDIC_GPIO2_INT_CLR : WO; bitpos: [2]; default: 0;
+ * Set this bit to clear the reg_gpio2_int_raw
+ * interrupt.
+ */
+#define DEDIC_GPIO2_INT_CLR    (BIT(2))
+#define DEDIC_GPIO2_INT_CLR_M  (DEDIC_GPIO2_INT_CLR_V << DEDIC_GPIO2_INT_CLR_S)
+#define DEDIC_GPIO2_INT_CLR_V  0x00000001
+#define DEDIC_GPIO2_INT_CLR_S  2
+/* DEDIC_GPIO3_INT_CLR : WO; bitpos: [3]; default: 0;
+ * Set this bit to clear the reg_gpio3_int_raw
+ * interrupt.
+ */
+#define DEDIC_GPIO3_INT_CLR    (BIT(3))
+#define DEDIC_GPIO3_INT_CLR_M  (DEDIC_GPIO3_INT_CLR_V << DEDIC_GPIO3_INT_CLR_S)
+#define DEDIC_GPIO3_INT_CLR_V  0x00000001
+#define DEDIC_GPIO3_INT_CLR_S  3
+/* DEDIC_GPIO4_INT_CLR : WO; bitpos: [4]; default: 0;
+ * Set this bit to clear the reg_gpio4_int_raw
+ * interrupt.
+ */
+#define DEDIC_GPIO4_INT_CLR    (BIT(4))
+#define DEDIC_GPIO4_INT_CLR_M  (DEDIC_GPIO4_INT_CLR_V << DEDIC_GPIO4_INT_CLR_S)
+#define DEDIC_GPIO4_INT_CLR_V  0x00000001
+#define DEDIC_GPIO4_INT_CLR_S  4
+/* DEDIC_GPIO5_INT_CLR : WO; bitpos: [5]; default: 0;
+ * Set this bit to clear the reg_gpio5_int_raw
+ * interrupt.
+ */
+#define DEDIC_GPIO5_INT_CLR    (BIT(5))
+#define DEDIC_GPIO5_INT_CLR_M  (DEDIC_GPIO5_INT_CLR_V << DEDIC_GPIO5_INT_CLR_S)
+#define DEDIC_GPIO5_INT_CLR_V  0x00000001
+#define DEDIC_GPIO5_INT_CLR_S  5
+/* DEDIC_GPIO6_INT_CLR : WO; bitpos: [6]; default: 0;
+ * Set this bit to clear the reg_gpio6_int_raw
+ * interrupt.
+ */
+#define DEDIC_GPIO6_INT_CLR    (BIT(6))
+#define DEDIC_GPIO6_INT_CLR_M  (DEDIC_GPIO6_INT_CLR_V << DEDIC_GPIO6_INT_CLR_S)
+#define DEDIC_GPIO6_INT_CLR_V  0x00000001
+#define DEDIC_GPIO6_INT_CLR_S  6
+/* DEDIC_GPIO7_INT_CLR : WO; bitpos: [7]; default: 0;
+ * Set this bit to clear the reg_gpio7_int_raw
+ * interrupt.
+ */
+#define DEDIC_GPIO7_INT_CLR    (BIT(7))
+#define DEDIC_GPIO7_INT_CLR_M  (DEDIC_GPIO7_INT_CLR_V << DEDIC_GPIO7_INT_CLR_S)
+#define DEDIC_GPIO7_INT_CLR_V  0x00000001
+#define DEDIC_GPIO7_INT_CLR_S  7
+
+#ifdef __cplusplus
+}
+#endif
+

+ 516 - 0
components/soc/soc/esp32s2/include/soc/dedic_gpio_struct.h

@@ -0,0 +1,516 @@
+/** Copyright 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.
+ */
+#pragma once
+
+#include <stdint.h>
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/** Configuration registers */
+/** Type of gpio_out_drt register
+ *  Dedicated GPIO Directive Output register
+ */
+typedef union {
+    struct {
+        /** gpio_out_drt_vlaue : WO; bitpos: [7:0]; default: 0;
+         *  This register is used to configure directive output value of 8-channel dedicated
+         *  gpio.
+         */
+        uint32_t gpio_out_drt_vlaue: 8;
+    };
+    uint32_t val;
+} dedic_gpio_out_drt_reg_t;
+
+/** Type of gpio_out_msk register
+ *  Dedicated GPIO Mask Output register
+ */
+typedef union {
+    struct {
+        /** gpio_out_value : WO; bitpos: [7:0]; default: 0;
+         *  This register is used to configure masked output value of 8-channel dedicated gpio.
+         */
+        uint32_t gpio_out_value: 8;
+        /** gpio_out_msk : WO; bitpos: [15:8]; default: 0;
+         *  This register is used to configure channels which would be masked. 1: corresponding
+         *  channel's output would be masked.
+         */
+        uint32_t gpio_out_msk: 8;
+    };
+    uint32_t val;
+} dedic_gpio_out_msk_reg_t;
+
+/** Type of gpio_out_idv register
+ *  Dedicated GPIO Individual Output register
+ */
+typedef union {
+    struct {
+        /** gpio_out_idv_ch0 : WO; bitpos: [1:0]; default: 0;
+         *  Configure channel 0 output value. 0: hold output value; 1: set output value; 2:
+         *  clear output value; 3: inverse output value.
+         */
+        uint32_t gpio_out_idv_ch0: 2;
+        /** gpio_out_idv_ch1 : WO; bitpos: [3:2]; default: 0;
+         *  Configure channel 1 output value. 0: hold output value; 1: set output value; 2:
+         *  clear output value; 3: inverse output value.
+         */
+        uint32_t gpio_out_idv_ch1: 2;
+        /** gpio_out_idv_ch2 : WO; bitpos: [5:4]; default: 0;
+         *  Configure channel 2 output value. 0: hold output value; 1: set output value; 2:
+         *  clear output value; 3: inverse output value.
+         */
+        uint32_t gpio_out_idv_ch2: 2;
+        /** gpio_out_idv_ch3 : WO; bitpos: [7:6]; default: 0;
+         *  Configure channel 3 output value. 0: hold output value; 1: set output value; 2:
+         *  clear output value; 3: inverse output value.
+         */
+        uint32_t gpio_out_idv_ch3: 2;
+        /** gpio_out_idv_ch4 : WO; bitpos: [9:8]; default: 0;
+         *  Configure channel 4 output value. 0: hold output value; 1: set output value; 2:
+         *  clear output value; 3: inverse output value.
+         */
+        uint32_t gpio_out_idv_ch4: 2;
+        /** gpio_out_idv_ch5 : WO; bitpos: [11:10]; default: 0;
+         *  Configure channel 5 output value. 0: hold output value; 1: set output value; 2:
+         *  clear output value; 3: inverse output value.
+         */
+        uint32_t gpio_out_idv_ch5: 2;
+        /** gpio_out_idv_ch6 : WO; bitpos: [13:12]; default: 0;
+         *  Configure channel 6 output value. 0: hold output value; 1: set output value; 2:
+         *  clear output value; 3: inverse output value.
+         */
+        uint32_t gpio_out_idv_ch6: 2;
+        /** gpio_out_idv_ch7 : WO; bitpos: [15:14]; default: 0;
+         *  Configure channel 7 output value. 0: hold output value; 1: set output value; 2:
+         *  clear output value; 3: inverse output value.
+         */
+        uint32_t gpio_out_idv_ch7: 2;
+    };
+    uint32_t val;
+} dedic_gpio_out_idv_reg_t;
+
+/** Type of gpio_out_cpu register
+ *  Dedicated GPIO Output Mode Select register
+ */
+typedef union {
+    struct {
+        /** gpio_out_cpu_sel0 : R/W; bitpos: [0]; default: 0;
+         *  Select gpio out value configured by registers or CPU instructors for channel 0. 1:
+         *  select CPU instructors.
+         */
+        uint32_t gpio_out_cpu_sel0: 1;
+        /** gpio_out_cpu_sel1 : R/W; bitpos: [1]; default: 0;
+         *  Select gpio out value configured by registers or CPU instructors for channel 1. 1:
+         *  select CPU instructors.
+         */
+        uint32_t gpio_out_cpu_sel1: 1;
+        /** gpio_out_cpu_sel2 : R/W; bitpos: [2]; default: 0;
+         *  Select gpio out value configured by registers or CPU instructors for channel 2. 1:
+         *  select CPU instructors.
+         */
+        uint32_t gpio_out_cpu_sel2: 1;
+        /** gpio_out_cpu_sel3 : R/W; bitpos: [3]; default: 0;
+         *  Select gpio out value configured by registers or CPU instructors for channel 3. 1:
+         *  select CPU instructors.
+         */
+        uint32_t gpio_out_cpu_sel3: 1;
+        /** gpio_out_cpu_sel4 : R/W; bitpos: [4]; default: 0;
+         *  Select gpio out value configured by registers or CPU instructors for channel 4. 1:
+         *  select CPU instructors.
+         */
+        uint32_t gpio_out_cpu_sel4: 1;
+        /** gpio_out_cpu_sel5 : R/W; bitpos: [5]; default: 0;
+         *  Select gpio out value configured by registers or CPU instructors for channel 5. 1:
+         *  select CPU instructors.
+         */
+        uint32_t gpio_out_cpu_sel5: 1;
+        /** gpio_out_cpu_sel6 : R/W; bitpos: [6]; default: 0;
+         *  Select gpio out value configured by registers or CPU instructors for channel 6. 1:
+         *  select CPU instructors.
+         */
+        uint32_t gpio_out_cpu_sel6: 1;
+        /** gpio_out_cpu_sel7 : R/W; bitpos: [7]; default: 0;
+         *  Select gpio out value configured by registers or CPU instructors for channel 7. 1:
+         *  select CPU instructors.
+         */
+        uint32_t gpio_out_cpu_sel7: 1;
+    };
+    uint32_t val;
+} dedic_gpio_out_cpu_reg_t;
+
+/** Type of gpio_in_dly register
+ *  Dedicated GPIO Input Delay Configuration register
+ */
+typedef union {
+    struct {
+        /** gpio_in_dly_ch0 : R/W; bitpos: [1:0]; default: 0;
+         *  Configure gpio 0 input delay. 0: No delay; 1: one clock delay; 2: two clock delay;
+         *  3: three clock delay.
+         */
+        uint32_t gpio_in_dly_ch0: 2;
+        /** gpio_in_dly_ch1 : R/W; bitpos: [3:2]; default: 0;
+         *  Configure gpio 1 input delay. 0: No delay; 1: one clock delay; 2: two clock delay;
+         *  3: three clock delay.
+         */
+        uint32_t gpio_in_dly_ch1: 2;
+        /** gpio_in_dly_ch2 : R/W; bitpos: [5:4]; default: 0;
+         *  Configure gpio 2 input delay. 0: No delay; 1: one clock delay; 2: two clock delay;
+         *  3: three clock delay.
+         */
+        uint32_t gpio_in_dly_ch2: 2;
+        /** gpio_in_dly_ch3 : R/W; bitpos: [7:6]; default: 0;
+         *  Configure gpio 3 input delay. 0: No delay; 1: one clock delay; 2: two clock delay;
+         *  3: three clock delay.
+         */
+        uint32_t gpio_in_dly_ch3: 2;
+        /** gpio_in_dly_ch4 : R/W; bitpos: [9:8]; default: 0;
+         *  Configure gpio 4 input delay. 0: No delay; 1: one clock delay; 2: two clock delay;
+         *  3: three clock delay.
+         */
+        uint32_t gpio_in_dly_ch4: 2;
+        /** gpio_in_dly_ch5 : R/W; bitpos: [11:10]; default: 0;
+         *  Configure gpio 5 input delay. 0: No delay; 1: one clock delay; 2: two clock delay;
+         *  3: three clock delay.
+         */
+        uint32_t gpio_in_dly_ch5: 2;
+        /** gpio_in_dly_ch6 : R/W; bitpos: [13:12]; default: 0;
+         *  Configure gpio 6 input delay. 0: No delay; 1: one clock delay; 2: two clock delay;
+         *  3: three clock delay.
+         */
+        uint32_t gpio_in_dly_ch6: 2;
+        /** gpio_in_dly_ch7 : R/W; bitpos: [15:14]; default: 0;
+         *  Configure gpio 7 input delay. 0: No delay; 1: one clock delay; 2: two clock delay;
+         *  3: three clock delay.
+         */
+        uint32_t gpio_in_dly_ch7: 2;
+    };
+    uint32_t val;
+} dedic_gpio_in_dly_reg_t;
+
+/** Type of gpio_intr_rcgn register
+ *  Dedicated GPIO Interrupts Generate Mode register
+ */
+typedef union {
+    struct {
+        /** gpio_intr_mode_ch0 : R/W; bitpos: [2:0]; default: 0;
+         *  Configure channel 0 interrupt generate mode.
+         *  0/1: do not generate interrupt;
+         *  2: low level trigger;
+         *  3: high level trigger;
+         *  4: falling edge trigger;
+         *  5: raising edge trigger;
+         *  6/7: falling and raising edge trigger.
+         */
+        uint32_t gpio_intr_mode_ch0: 3;
+        /** gpio_intr_mode_ch1 : R/W; bitpos: [5:3]; default: 0;
+         *  Configure channel 1 interrupt generate mode.
+         *  0/1: do not generate interrupt;
+         *  2: low level trigger;
+         *  3: high level trigger;
+         *  4: falling edge trigger;
+         *  5: raising edge trigger;
+         *  6/7: falling and raising edge trigger.
+         */
+        uint32_t gpio_intr_mode_ch1: 3;
+        /** gpio_intr_mode_ch2 : R/W; bitpos: [8:6]; default: 0;
+         *  Configure channel 2 interrupt generate mode.
+         *  0/1: do not generate interrupt;
+         *  2: low level trigger;
+         *  3: high level trigger;
+         *  4: falling edge trigger;
+         *  5: raising edge trigger;
+         *  6/7: falling and raising edge trigger.
+         */
+        uint32_t gpio_intr_mode_ch2: 3;
+        /** gpio_intr_mode_ch3 : R/W; bitpos: [11:9]; default: 0;
+         *  Configure channel 3 interrupt generate mode.
+         *  0/1: do not generate interrupt;
+         *  2: low level trigger;
+         *  3: high level trigger;
+         *  4: falling edge trigger;
+         *  5: raising edge trigger;
+         *  6/7: falling and raising edge trigger.
+         */
+        uint32_t gpio_intr_mode_ch3: 3;
+        /** gpio_intr_mode_ch4 : R/W; bitpos: [14:12]; default: 0;
+         *  Configure channel 4 interrupt generate mode.
+         *  0/1: do not generate interrupt;
+         *  2: low level trigger;
+         *  3: high level trigger;
+         *  4: falling edge trigger;
+         *  5: raising edge trigger;
+         *  6/7: falling and raising edge trigger.
+         */
+        uint32_t gpio_intr_mode_ch4: 3;
+        /** gpio_intr_mode_ch5 : R/W; bitpos: [17:15]; default: 0;
+         *  Configure channel 5 interrupt generate mode.
+         *  0/1: do not generate interrupt;
+         *  2: low level trigger;
+         *  3: high level trigger;
+         *  4: falling edge trigger;
+         *  5: raising edge trigger;
+         *  6/7: falling and raising edge trigger.
+         */
+        uint32_t gpio_intr_mode_ch5: 3;
+        /** gpio_intr_mode_ch6 : R/W; bitpos: [20:18]; default: 0;
+         *  Configure channel 6 interrupt generate mode.
+         *  0/1: do not generate interrupt;
+         *  2: low level trigger;
+         *  3: high level trigger;
+         *  4: falling edge trigger;
+         *  5: raising edge trigger;
+         *  6/7: falling and raising edge trigger.
+         */
+        uint32_t gpio_intr_mode_ch6: 3;
+        /** gpio_intr_mode_ch7 : R/W; bitpos: [23:21]; default: 0;
+         *  Configure channel 7 interrupt generate mode.
+         *  0/1: do not generate interrupt;
+         *  2: low level trigger;
+         *  3: high level trigger;
+         *  4: falling edge trigger;
+         *  5: raising edge trigger;
+         *  6/7: falling and raising edge trigger.
+         */
+        uint32_t gpio_intr_mode_ch7: 3;
+    };
+    uint32_t val;
+} dedic_gpio_intr_rcgn_reg_t;
+
+
+/** Status registers */
+/** Type of gpio_out_scan register
+ *  Dedicated GPIO Output Status register
+ */
+typedef union {
+    struct {
+        /** gpio_out_status : RO; bitpos: [7:0]; default: 0;
+         *  gpio out value configured by DEDIC_GPIO_OUT_DRT_REG, DEDIC_GPIO_OUT_MSK_REG,
+         *  DEDIC_GPIO_OUT_IDV_REG.
+         */
+        uint32_t gpio_out_status: 8;
+    };
+    uint32_t val;
+} dedic_gpio_out_scan_reg_t;
+
+/** Type of gpio_in_scan register
+ *  Dedicated GPIO Input Status register
+ */
+typedef union {
+    struct {
+        /** gpio_in_status : RO; bitpos: [7:0]; default: 0;
+         *  gpio in value after configured by DEDIC_GPIO_IN_DLY_REG.
+         */
+        uint32_t gpio_in_status: 8;
+    };
+    uint32_t val;
+} dedic_gpio_in_scan_reg_t;
+
+
+/** Interrupt registers */
+/** Type of gpio_intr_raw register
+ *  Raw interrupt status
+ */
+typedef union {
+    struct {
+        /** gpio0_int_raw : RO; bitpos: [0]; default: 0;
+         *  This interrupt raw bit turns to high level when dedicated GPIO 0 has level/edge
+         *  change configured by DEDIC_GPIO_INTR_RCGN_REG.
+         */
+        uint32_t gpio0_int_raw: 1;
+        /** gpio1_int_raw : RO; bitpos: [1]; default: 0;
+         *  This interrupt raw bit turns to high level when dedicated GPIO 1 has level/edge
+         *  change configured by DEDIC_GPIO_INTR_RCGN_REG.
+         */
+        uint32_t gpio1_int_raw: 1;
+        /** gpio2_int_raw : RO; bitpos: [2]; default: 0;
+         *  This interrupt raw bit turns to high level when dedicated GPIO 2 has level/edge
+         *  change configured by DEDIC_GPIO_INTR_RCGN_REG.
+         */
+        uint32_t gpio2_int_raw: 1;
+        /** gpio3_int_raw : RO; bitpos: [3]; default: 0;
+         *  This interrupt raw bit turns to high level when dedicated GPIO 3 has level/edge
+         *  change configured by DEDIC_GPIO_INTR_RCGN_REG.
+         */
+        uint32_t gpio3_int_raw: 1;
+        /** gpio4_int_raw : RO; bitpos: [4]; default: 0;
+         *  This interrupt raw bit turns to high level when dedicated GPIO 4 has level/edge
+         *  change configured by DEDIC_GPIO_INTR_RCGN_REG.
+         */
+        uint32_t gpio4_int_raw: 1;
+        /** gpio5_int_raw : RO; bitpos: [5]; default: 0;
+         *  This interrupt raw bit turns to high level when dedicated GPIO 5 has level/edge
+         *  change configured by DEDIC_GPIO_INTR_RCGN_REG.
+         */
+        uint32_t gpio5_int_raw: 1;
+        /** gpio6_int_raw : RO; bitpos: [6]; default: 0;
+         *  This interrupt raw bit turns to high level when dedicated GPIO 6 has level/edge
+         *  change configured by DEDIC_GPIO_INTR_RCGN_REG.
+         */
+        uint32_t gpio6_int_raw: 1;
+        /** gpio7_int_raw : RO; bitpos: [7]; default: 0;
+         *  This interrupt raw bit turns to high level when dedicated GPIO 7 has level/edge
+         *  change configured by DEDIC_GPIO_INTR_RCGN_REG.
+         */
+        uint32_t gpio7_int_raw: 1;
+    };
+    uint32_t val;
+} dedic_gpio_intr_raw_reg_t;
+
+/** Type of gpio_intr_rls register
+ *  Interrupt enable bits
+ */
+typedef union {
+    struct {
+        /** gpio0_int_ena : R/W; bitpos: [0]; default: 0;
+         *  This enable bit for reg_gpio0_int_st register.
+         */
+        uint32_t gpio0_int_ena: 1;
+        /** gpio1_int_ena : R/W; bitpos: [1]; default: 0;
+         *  This enable bit for reg_gpio1_int_st register.
+         */
+        uint32_t gpio1_int_ena: 1;
+        /** gpio2_int_ena : R/W; bitpos: [2]; default: 0;
+         *  This enable bit for reg_gpio2_int_st register.
+         */
+        uint32_t gpio2_int_ena: 1;
+        /** gpio3_int_ena : R/W; bitpos: [3]; default: 0;
+         *  This enable bit for reg_gpio3_int_st register.
+         */
+        uint32_t gpio3_int_ena: 1;
+        /** gpio4_int_ena : R/W; bitpos: [4]; default: 0;
+         *  This enable bit for reg_gpio4_int_st register.
+         */
+        uint32_t gpio4_int_ena: 1;
+        /** gpio5_int_ena : R/W; bitpos: [5]; default: 0;
+         *  This enable bit for reg_gpio5_int_st register.
+         */
+        uint32_t gpio5_int_ena: 1;
+        /** gpio6_int_ena : R/W; bitpos: [6]; default: 0;
+         *  This enable bit for reg_gpio6_int_st register.
+         */
+        uint32_t gpio6_int_ena: 1;
+        /** gpio7_int_ena : R/W; bitpos: [7]; default: 0;
+         *  This enable bit for reg_gpio7_int_st register.
+         */
+        uint32_t gpio7_int_ena: 1;
+    };
+    uint32_t val;
+} dedic_gpio_intr_rls_reg_t;
+
+/** Type of gpio_intr_st register
+ *  Masked interrupt status
+ */
+typedef union {
+    struct {
+        /** gpio0_int_st : RO; bitpos: [0]; default: 0;
+         *  This is the status bit for reg_gpio0_int_raw when reg_gpio0_int_ena is set to 1.
+         */
+        uint32_t gpio0_int_st: 1;
+        /** gpio1_int_st : RO; bitpos: [1]; default: 0;
+         *  This is the status bit for reg_gpio1_int_raw when reg_gpio1_int_ena is set to 1.
+         */
+        uint32_t gpio1_int_st: 1;
+        /** gpio2_int_st : RO; bitpos: [2]; default: 0;
+         *  This is the status bit for reg_gpio2_int_raw when reg_gpio2_int_ena is set to 1.
+         */
+        uint32_t gpio2_int_st: 1;
+        /** gpio3_int_st : RO; bitpos: [3]; default: 0;
+         *  This is the status bit for reg_gpio3_int_raw when reg_gpio3_int_ena is set to 1.
+         */
+        uint32_t gpio3_int_st: 1;
+        /** gpio4_int_st : RO; bitpos: [4]; default: 0;
+         *  This is the status bit for reg_gpio4_int_raw when reg_gpio4_int_ena is set to 1.
+         */
+        uint32_t gpio4_int_st: 1;
+        /** gpio5_int_st : RO; bitpos: [5]; default: 0;
+         *  This is the status bit for reg_gpio5_int_raw when reg_gpio5_int_ena is set to 1.
+         */
+        uint32_t gpio5_int_st: 1;
+        /** gpio6_int_st : RO; bitpos: [6]; default: 0;
+         *  This is the status bit for reg_gpio6_int_raw when reg_gpio6_int_ena is set to 1.
+         */
+        uint32_t gpio6_int_st: 1;
+        /** gpio7_int_st : RO; bitpos: [7]; default: 0;
+         *  This is the status bit for reg_gpio7_int_raw when reg_gpio7_int_ena is set to 1.
+         */
+        uint32_t gpio7_int_st: 1;
+    };
+    uint32_t val;
+} dedic_gpio_intr_st_reg_t;
+
+/** Type of gpio_intr_clr register
+ *  Interrupt clear bits
+ */
+typedef union {
+    struct {
+        /** gpio0_int_clr : WO; bitpos: [0]; default: 0;
+         *  Set this bit to clear the reg_gpio0_int_raw interrupt.
+         */
+        uint32_t gpio0_int_clr: 1;
+        /** gpio1_int_clr : WO; bitpos: [1]; default: 0;
+         *  Set this bit to clear the reg_gpio1_int_raw interrupt.
+         */
+        uint32_t gpio1_int_clr: 1;
+        /** gpio2_int_clr : WO; bitpos: [2]; default: 0;
+         *  Set this bit to clear the reg_gpio2_int_raw interrupt.
+         */
+        uint32_t gpio2_int_clr: 1;
+        /** gpio3_int_clr : WO; bitpos: [3]; default: 0;
+         *  Set this bit to clear the reg_gpio3_int_raw interrupt.
+         */
+        uint32_t gpio3_int_clr: 1;
+        /** gpio4_int_clr : WO; bitpos: [4]; default: 0;
+         *  Set this bit to clear the reg_gpio4_int_raw interrupt.
+         */
+        uint32_t gpio4_int_clr: 1;
+        /** gpio5_int_clr : WO; bitpos: [5]; default: 0;
+         *  Set this bit to clear the reg_gpio5_int_raw interrupt.
+         */
+        uint32_t gpio5_int_clr: 1;
+        /** gpio6_int_clr : WO; bitpos: [6]; default: 0;
+         *  Set this bit to clear the reg_gpio6_int_raw interrupt.
+         */
+        uint32_t gpio6_int_clr: 1;
+        /** gpio7_int_clr : WO; bitpos: [7]; default: 0;
+         *  Set this bit to clear the reg_gpio7_int_raw interrupt.
+         */
+        uint32_t gpio7_int_clr: 1;
+    };
+    uint32_t val;
+} dedic_gpio_intr_clr_reg_t;
+
+typedef struct {
+    volatile dedic_gpio_out_drt_reg_t gpio_out_drt;
+    volatile dedic_gpio_out_msk_reg_t gpio_out_msk;
+    volatile dedic_gpio_out_idv_reg_t gpio_out_idv;
+    volatile dedic_gpio_out_scan_reg_t gpio_out_scan;
+    volatile dedic_gpio_out_cpu_reg_t gpio_out_cpu;
+    volatile dedic_gpio_in_dly_reg_t gpio_in_dly;
+    volatile dedic_gpio_in_scan_reg_t gpio_in_scan;
+    volatile dedic_gpio_intr_rcgn_reg_t gpio_intr_rcgn;
+    volatile dedic_gpio_intr_raw_reg_t gpio_intr_raw;
+    volatile dedic_gpio_intr_rls_reg_t gpio_intr_rls;
+    volatile dedic_gpio_intr_st_reg_t gpio_intr_st;
+    volatile dedic_gpio_intr_clr_reg_t gpio_intr_clr;
+} dedic_dev_t;
+
+_Static_assert(sizeof(dedic_dev_t) == 0x30, "dedic_dev_t should occupy 0x30 bytes in memory");
+
+extern dedic_dev_t DEDIC_GPIO;
+
+#ifdef __cplusplus
+}
+#endif

+ 1 - 0
components/soc/soc/esp32s2/include/soc/periph_defs.h

@@ -54,6 +54,7 @@ typedef enum {
     PERIPH_CRYPTO_DMA_MODULE,        //this DMA is shared between AES and SHA
     PERIPH_AES_DMA_MODULE,
     PERIPH_SHA_DMA_MODULE,
+    PERIPH_DEDIC_GPIO_MODULE,
     PERIPH_MODULE_MAX
 } periph_module_t;
 

+ 1 - 1
components/soc/soc/esp32s2/include/soc/soc.h

@@ -66,7 +66,7 @@
 #define DR_REG_PCNT_BASE                        0x3f417000
 #define DR_REG_SLC_BASE                         0x3f418000
 #define DR_REG_LEDC_BASE                        0x3f419000
-#define DR_REG_MCP_BASE                         0x3f4c3000
+#define DR_REG_CP_BASE                          0x3f4c3000
 #define DR_REG_EFUSE_BASE                       0x3f41A000
 #define DR_REG_NRX_BASE                         0x3f41CC00
 #define DR_REG_BB_BASE                          0x3f41D000

+ 8 - 1
components/soc/soc/esp32s2/include/soc/soc_caps.h

@@ -40,6 +40,7 @@
 #define SOC_TWAI_SUPPORTED 1
 #define SOC_CP_DMA_SUPPORTED 1
 #define SOC_CPU_CORES_NUM 1
+#define SOC_DEDICATED_GPIO_SUPPORTED 1
 #define SOC_SUPPORTS_SECURE_DL_MODE 1
 #define SOC_RISCV_COPROC_SUPPORTED 1
 #define SOC_USB_SUPPORTED 1
@@ -95,6 +96,12 @@
 // GPIO 46, 47 are input only
 #define SOC_GPIO_VALID_OUTPUT_GPIO_MASK     (SOC_GPIO_VALID_GPIO_MASK & ~(0ULL | BIT46 | BIT47))
 
+/*-------------------------- Dedicated GPIO CAPS ---------------------------------------*/
+#define SOC_DEDIC_GPIO_OUT_CHANNELS_NUM (8) /*!< 8 outward channels on each CPU core */
+#define SOC_DEDIC_GPIO_IN_CHANNELS_NUM  (8) /*!< 8 inward channels on each CPU core */
+#define SOC_DEDIC_GPIO_ALLOW_REG_ACCESS (1) /*!< Allow access dedicated GPIO channel by register */
+#define SOC_DEDIC_GPIO_HAS_INTERRUPT    (1) /*!< Dedicated GPIO has its own interrupt source */
+
 /*-------------------------- I2C CAPS ----------------------------------------*/
 // ESP32-S2 have 2 I2C.
 #define SOC_I2C_NUM            (2)
@@ -207,4 +214,4 @@
 #define SOC_USB_PERIPH_NUM 1
 
 /* ---------------------------- Compatibility ------------------------------- */
-// No contents
+// No contents

+ 1 - 0
components/soc/soc/esp32s3/CMakeLists.txt

@@ -1,6 +1,7 @@
 add_library(soc_esp32s3 STATIC
     "adc_periph.c"
     "dac_periph.c"
+    "dedic_gpio_periph.c"
     "gpio_periph.c"
     "i2c_periph.c"
     "i2s_periph.c"

+ 51 - 0
components/soc/soc/esp32s3/dedic_gpio_periph.c

@@ -0,0 +1,51 @@
+// Copyright 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.
+
+#include "soc/dedic_gpio_periph.h"
+#include "soc/gpio_sig_map.h"
+
+const dedic_gpio_signal_conn_t dedic_gpio_periph_signals = {
+    .module = PERIPH_DEDIC_GPIO_MODULE,
+    .irq = -1,
+    .cores = {
+        [0] = {
+            .in_sig_per_channel = {
+                [0] = PRO_ALONEGPIO_IN0_IDX,
+                [1] = PRO_ALONEGPIO_IN1_IDX,
+                [2] = PRO_ALONEGPIO_IN2_IDX,
+                [3] = PRO_ALONEGPIO_IN3_IDX,
+            },
+            .out_sig_per_channel = {
+                [0] = PRO_ALONEGPIO_OUT0_IDX,
+                [1] = PRO_ALONEGPIO_OUT1_IDX,
+                [2] = PRO_ALONEGPIO_OUT2_IDX,
+                [3] = PRO_ALONEGPIO_OUT3_IDX,
+            }
+        },
+        [1] = {
+            .in_sig_per_channel = {
+                [0] = PRO_ALONEGPIO_IN4_IDX,
+                [1] = PRO_ALONEGPIO_IN5_IDX,
+                [2] = PRO_ALONEGPIO_IN6_IDX,
+                [3] = PRO_ALONEGPIO_IN7_IDX,
+            },
+            .out_sig_per_channel = {
+                [0] = PRO_ALONEGPIO_OUT4_IDX,
+                [1] = PRO_ALONEGPIO_OUT5_IDX,
+                [2] = PRO_ALONEGPIO_OUT6_IDX,
+                [3] = PRO_ALONEGPIO_OUT7_IDX,
+            }
+        },
+    },
+};

+ 1 - 0
components/soc/soc/esp32s3/include/soc/periph_defs.h

@@ -55,6 +55,7 @@ typedef enum {
     PERIPH_RSA_MODULE,
     PERIPH_SYSTIMER_MODULE,
     PERIPH_GDMA_MODULE,
+    PERIPH_DEDIC_GPIO_MODULE,
     PERIPH_MODULE_MAX
 } periph_module_t;
 

+ 1 - 1
components/soc/soc/esp32s3/include/soc/soc.h

@@ -41,9 +41,9 @@
 #define DR_REG_RSA_BASE                         0x6003c000
 #define DR_REG_HMAC_BASE                        0x6003e000
 #define DR_REG_DIGITAL_SIGNATURE_BASE           0x6003d000
+#define DR_REG_GDMA_BASE                        0x6003f000
 #define DR_REG_CRYPTO_DMA_BASE                  0x6003f000
 #define DR_REG_ASSIST_DEBUG_BASE                0x600ce000
-#define DR_REG_DEDICATED_GPIO_BASE              0x600cf000
 #define DR_REG_WORLD_CNTL_BASE                  0x600d0000
 #define DR_REG_DPORT_END                        0x600d3FFC
 #define DR_REG_UART_BASE                        0x60000000

+ 5 - 0
components/soc/soc/esp32s3/include/soc/soc_caps.h

@@ -9,6 +9,7 @@
 #define SOC_PCNT_SUPPORTED 1
 #define SOC_TWAI_SUPPORTED 1
 #define SOC_GDMA_SUPPORTED 1
+#define SOC_DEDICATED_GPIO_SUPPORTED 1
 #define SOC_CPU_CORES_NUM 2
 #define SOC_CACHE_SUPPORT_WRAP    1
 
@@ -30,6 +31,10 @@
 /*-------------------------- GPIO CAPS ---------------------------------------*/
 #include "gpio_caps.h"
 
+/*-------------------------- Dedicated GPIO CAPS -----------------------------*/
+#define SOC_DEDIC_GPIO_OUT_CHANNELS_NUM (4) /*!< 4 outward channels on each CPU core */
+#define SOC_DEDIC_GPIO_IN_CHANNELS_NUM  (4) /*!< 4 inward channels on each CPU core */
+
 /*-------------------------- I2C CAPS ----------------------------------------*/
 #include "i2c_caps.h"
 

+ 41 - 0
components/soc/soc/include/soc/dedic_gpio_periph.h

@@ -0,0 +1,41 @@
+// Copyright 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.
+
+#pragma once
+
+#include <stdint.h>
+#include "soc/soc.h"
+#include "soc/soc_caps.h"
+#include "soc/periph_defs.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#if SOC_DEDICATED_GPIO_SUPPORTED
+typedef struct {
+    const periph_module_t module; // Peripheral module
+    const int irq;                // Interrupt resource (-1 means no interrupt supported)
+    struct {
+        const int in_sig_per_channel[SOC_DEDIC_GPIO_IN_CHANNELS_NUM];
+        const int out_sig_per_channel[SOC_DEDIC_GPIO_OUT_CHANNELS_NUM];
+    } cores[SOC_CPU_CORES_NUM]; // Signals routed to/from GPIO matrix
+} dedic_gpio_signal_conn_t;
+
+extern const dedic_gpio_signal_conn_t dedic_gpio_periph_signals;
+#endif // SOC_DEDICATED_GPIO_SUPPORTED
+
+#ifdef __cplusplus
+}
+#endif