esp32h2: copy driver/hal/soc components from esp32c3

Copy the esp32c3 code without any change:
 * components/driver/esp32h2
 * components/esp32h2
 * components/hal/esp32h2
 * components/soc/esp32h2
This commit is contained in:
Shu Chen 2021-06-10 10:22:35 +08:00
parent be9864fa4b
commit 983cca8b27
156 changed files with 63689 additions and 0 deletions

View File

@ -0,0 +1,717 @@
/*
* SPDX-FileCopyrightText: 2016-2021 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <esp_types.h>
#include <stdlib.h>
#include <ctype.h>
#include <string.h>
#include "sdkconfig.h"
#include "esp_intr_alloc.h"
#include "esp_log.h"
#include "esp_pm.h"
#include "sys/lock.h"
#include "freertos/FreeRTOS.h"
#include "freertos/semphr.h"
#include "freertos/timers.h"
#include "freertos/ringbuf.h"
#include "esp32c3/rom/ets_sys.h"
#include "driver/periph_ctrl.h"
#include "driver/gpio.h"
#include "driver/adc.h"
#include "hal/adc_types.h"
#include "hal/adc_hal.h"
#include "hal/dma_types.h"
#include "esp_efuse_rtc_calib.h"
#include "esp_private/gdma.h"
#define ADC_CHECK_RET(fun_ret) ({ \
if (fun_ret != ESP_OK) { \
ESP_LOGE(ADC_TAG,"%s(%d)",__FUNCTION__,__LINE__); \
return ESP_FAIL; \
} \
})
static const char *ADC_TAG = "ADC";
#define ADC_CHECK(a, str, ret_val) ({ \
if (!(a)) { \
ESP_LOGE(ADC_TAG,"%s(%d) :%s", __FUNCTION__, __LINE__, str); \
return (ret_val); \
} \
})
#define ADC_GET_IO_NUM(periph, channel) (adc_channel_io_map[periph][channel])
#define ADC_CHANNEL_CHECK(periph, channel) ADC_CHECK(channel < SOC_ADC_CHANNEL_NUM(periph), "ADC"#periph" channel error", ESP_ERR_INVALID_ARG)
extern portMUX_TYPE rtc_spinlock; //TODO: Will be placed in the appropriate position after the rtc module is finished.
#define ADC_ENTER_CRITICAL() portENTER_CRITICAL(&rtc_spinlock)
#define ADC_EXIT_CRITICAL() portEXIT_CRITICAL(&rtc_spinlock)
/**
* 1. sar_adc1_lock: this mutex lock is to protect the SARADC1 module.
* 2. sar_adc2_lock: this mutex lock is to protect the SARADC2 module. On C3, it is controlled by the digital controller
* and PWDET controller.
* 3. adc_reg_lock: this spin lock is to protect the shared registers used by ADC1 / ADC2 single read mode.
*/
static _lock_t sar_adc1_lock;
#define SAR_ADC1_LOCK_ACQUIRE() _lock_acquire(&sar_adc1_lock)
#define SAR_ADC1_LOCK_RELEASE() _lock_release(&sar_adc1_lock)
static _lock_t sar_adc2_lock;
#define SAR_ADC2_LOCK_ACQUIRE() _lock_acquire(&sar_adc2_lock)
#define SAR_ADC2_LOCK_RELEASE() _lock_release(&sar_adc2_lock)
portMUX_TYPE adc_reg_lock = portMUX_INITIALIZER_UNLOCKED;
#define ADC_REG_LOCK_ENTER() portENTER_CRITICAL(&adc_reg_lock)
#define ADC_REG_LOCK_EXIT() portEXIT_CRITICAL(&adc_reg_lock)
#define INTERNAL_BUF_NUM 5
#define IN_SUC_EOF_BIT GDMA_LL_EVENT_RX_SUC_EOF
/*---------------------------------------------------------------
Digital Controller Context
---------------------------------------------------------------*/
typedef struct adc_digi_context_t {
uint8_t *rx_dma_buf; //dma buffer
adc_hal_context_t hal; //hal context
gdma_channel_handle_t rx_dma_channel; //dma rx channel handle
RingbufHandle_t ringbuf_hdl; //RX ringbuffer handler
intptr_t rx_eof_desc_addr; //eof descriptor address of RX channel
bool ringbuf_overflow_flag; //1: ringbuffer overflow
bool driver_start_flag; //1: driver is started; 0: driver is stoped
bool use_adc1; //1: ADC unit1 will be used; 0: ADC unit1 won't be used.
bool use_adc2; //1: ADC unit2 will be used; 0: ADC unit2 won't be used. This determines whether to acquire sar_adc2_mutex lock or not.
adc_atten_t adc1_atten; //Attenuation for ADC1. On this chip each ADC can only support one attenuation.
adc_atten_t adc2_atten; //Attenuation for ADC2. On this chip each ADC can only support one attenuation.
adc_digi_config_t digi_controller_config; //Digital Controller Configuration
esp_pm_lock_handle_t pm_lock; //For power management
} adc_digi_context_t;
static adc_digi_context_t *s_adc_digi_ctx = NULL;
static uint32_t adc_get_calibration_offset(adc_ll_num_t adc_n, adc_channel_t chan, adc_atten_t atten);
/*---------------------------------------------------------------
ADC Continuous Read Mode (via DMA)
---------------------------------------------------------------*/
static IRAM_ATTR bool adc_dma_in_suc_eof_callback(gdma_channel_handle_t dma_chan, gdma_event_data_t *event_data, void *user_data);
static int8_t adc_digi_get_io_num(uint8_t adc_unit, uint8_t adc_channel)
{
return adc_channel_io_map[adc_unit][adc_channel];
}
static esp_err_t adc_digi_gpio_init(adc_unit_t adc_unit, uint16_t channel_mask)
{
esp_err_t ret = ESP_OK;
uint64_t gpio_mask = 0;
uint32_t n = 0;
int8_t io = 0;
while (channel_mask) {
if (channel_mask & 0x1) {
io = adc_digi_get_io_num(adc_unit, n);
if (io < 0) {
return ESP_ERR_INVALID_ARG;
}
gpio_mask |= BIT64(io);
}
channel_mask = channel_mask >> 1;
n++;
}
gpio_config_t cfg = {
.pin_bit_mask = gpio_mask,
.mode = GPIO_MODE_DISABLE,
};
ret = gpio_config(&cfg);
return ret;
}
esp_err_t adc_digi_initialize(const adc_digi_init_config_t *init_config)
{
esp_err_t ret = ESP_OK;
s_adc_digi_ctx = calloc(1, sizeof(adc_digi_context_t));
if (s_adc_digi_ctx == NULL) {
ret = ESP_ERR_NO_MEM;
goto cleanup;
}
//ringbuffer
s_adc_digi_ctx->ringbuf_hdl = xRingbufferCreate(init_config->max_store_buf_size, RINGBUF_TYPE_BYTEBUF);
if (!s_adc_digi_ctx->ringbuf_hdl) {
ret = ESP_ERR_NO_MEM;
goto cleanup;
}
//malloc internal buffer used by DMA
s_adc_digi_ctx->rx_dma_buf = heap_caps_calloc(1, init_config->conv_num_each_intr * INTERNAL_BUF_NUM, MALLOC_CAP_INTERNAL);
if (!s_adc_digi_ctx->rx_dma_buf) {
ret = ESP_ERR_NO_MEM;
goto cleanup;
}
//malloc dma descriptor
s_adc_digi_ctx->hal.rx_desc = heap_caps_calloc(1, (sizeof(dma_descriptor_t)) * INTERNAL_BUF_NUM, MALLOC_CAP_DMA);
if (!s_adc_digi_ctx->hal.rx_desc) {
ret = ESP_ERR_NO_MEM;
goto cleanup;
}
//malloc pattern table
s_adc_digi_ctx->digi_controller_config.adc_pattern = calloc(1, SOC_ADC_PATT_LEN_MAX * sizeof(adc_digi_pattern_table_t));
if (!s_adc_digi_ctx->digi_controller_config.adc_pattern) {
ret = ESP_ERR_NO_MEM;
goto cleanup;
}
#if CONFIG_PM_ENABLE
ret = esp_pm_lock_create(ESP_PM_APB_FREQ_MAX, 0, "adc_dma", &s_adc_digi_ctx->pm_lock);
if (ret != ESP_OK) {
goto cleanup;
}
#endif //CONFIG_PM_ENABLE
//init gpio pins
if (init_config->adc1_chan_mask) {
ret = adc_digi_gpio_init(ADC_NUM_1, init_config->adc1_chan_mask);
if (ret != ESP_OK) {
goto cleanup;
}
}
if (init_config->adc2_chan_mask) {
ret = adc_digi_gpio_init(ADC_NUM_2, init_config->adc2_chan_mask);
if (ret != ESP_OK) {
goto cleanup;
}
}
//alloc rx gdma channel
gdma_channel_alloc_config_t rx_alloc_config = {
.direction = GDMA_CHANNEL_DIRECTION_RX,
};
ret = gdma_new_channel(&rx_alloc_config, &s_adc_digi_ctx->rx_dma_channel);
if (ret != ESP_OK) {
goto cleanup;
}
gdma_connect(s_adc_digi_ctx->rx_dma_channel, GDMA_MAKE_TRIGGER(GDMA_TRIG_PERIPH_ADC, 0));
gdma_strategy_config_t strategy_config = {
.auto_update_desc = true,
.owner_check = true
};
gdma_apply_strategy(s_adc_digi_ctx->rx_dma_channel, &strategy_config);
gdma_rx_event_callbacks_t cbs = {
.on_recv_eof = adc_dma_in_suc_eof_callback
};
gdma_register_rx_event_callbacks(s_adc_digi_ctx->rx_dma_channel, &cbs, s_adc_digi_ctx);
int dma_chan;
gdma_get_channel_id(s_adc_digi_ctx->rx_dma_channel, &dma_chan);
adc_hal_config_t config = {
.desc_max_num = INTERNAL_BUF_NUM,
.dma_chan = dma_chan,
.eof_num = init_config->conv_num_each_intr / ADC_HAL_DATA_LEN_PER_CONV
};
adc_hal_context_config(&s_adc_digi_ctx->hal, &config);
//enable SARADC module clock
periph_module_enable(PERIPH_SARADC_MODULE);
adc_hal_calibration_init(ADC_NUM_1);
adc_hal_calibration_init(ADC_NUM_2);
return ret;
cleanup:
adc_digi_deinitialize();
return ret;
}
static IRAM_ATTR bool adc_dma_intr(adc_digi_context_t *adc_digi_ctx);
static IRAM_ATTR bool adc_dma_in_suc_eof_callback(gdma_channel_handle_t dma_chan, gdma_event_data_t *event_data, void *user_data)
{
assert(event_data);
adc_digi_context_t *adc_digi_ctx = (adc_digi_context_t *)user_data;
adc_digi_ctx->rx_eof_desc_addr = event_data->rx_eof_desc_addr;
return adc_dma_intr(adc_digi_ctx);
}
static IRAM_ATTR bool adc_dma_intr(adc_digi_context_t *adc_digi_ctx)
{
portBASE_TYPE taskAwoken = 0;
BaseType_t ret;
adc_hal_dma_desc_status_t status = false;
dma_descriptor_t *current_desc = NULL;
while (1) {
status = adc_hal_get_reading_result(&adc_digi_ctx->hal, adc_digi_ctx->rx_eof_desc_addr, &current_desc);
if (status != ADC_HAL_DMA_DESC_VALID) {
break;
}
ret = xRingbufferSendFromISR(adc_digi_ctx->ringbuf_hdl, current_desc->buffer, current_desc->dw0.length, &taskAwoken);
if (ret == pdFALSE) {
//ringbuffer overflow
adc_digi_ctx->ringbuf_overflow_flag = 1;
}
}
if (status == ADC_HAL_DMA_DESC_NULL) {
//start next turns of dma operation
adc_hal_digi_rxdma_start(&adc_digi_ctx->hal, adc_digi_ctx->rx_dma_buf);
}
return (taskAwoken == pdTRUE);
}
esp_err_t adc_digi_start(void)
{
if (s_adc_digi_ctx->driver_start_flag != 0) {
ESP_LOGE(ADC_TAG, "The driver is already started");
return ESP_ERR_INVALID_STATE;
}
adc_power_acquire();
//reset flags
s_adc_digi_ctx->ringbuf_overflow_flag = 0;
s_adc_digi_ctx->driver_start_flag = 1;
if (s_adc_digi_ctx->use_adc1) {
SAR_ADC1_LOCK_ACQUIRE();
}
if (s_adc_digi_ctx->use_adc2) {
SAR_ADC2_LOCK_ACQUIRE();
}
#if CONFIG_PM_ENABLE
// Lock APB frequency while ADC driver is in use
esp_pm_lock_acquire(s_adc_digi_ctx->pm_lock);
#endif
adc_arbiter_t config = ADC_ARBITER_CONFIG_DEFAULT();
if (s_adc_digi_ctx->use_adc1) {
uint32_t cal_val = adc_get_calibration_offset(ADC_NUM_1, ADC_CHANNEL_MAX, s_adc_digi_ctx->adc1_atten);
adc_hal_set_calibration_param(ADC_NUM_1, cal_val);
}
if (s_adc_digi_ctx->use_adc2) {
uint32_t cal_val = adc_get_calibration_offset(ADC_NUM_2, ADC_CHANNEL_MAX, s_adc_digi_ctx->adc2_atten);
adc_hal_set_calibration_param(ADC_NUM_2, cal_val);
}
adc_hal_init();
adc_hal_arbiter_config(&config);
adc_hal_digi_init(&s_adc_digi_ctx->hal);
adc_hal_digi_controller_config(&s_adc_digi_ctx->digi_controller_config);
//reset ADC and DMA
adc_hal_fifo_reset(&s_adc_digi_ctx->hal);
//start DMA
adc_hal_digi_rxdma_start(&s_adc_digi_ctx->hal, s_adc_digi_ctx->rx_dma_buf);
//start ADC
adc_hal_digi_start(&s_adc_digi_ctx->hal);
return ESP_OK;
}
esp_err_t adc_digi_stop(void)
{
if (s_adc_digi_ctx->driver_start_flag != 1) {
ESP_LOGE(ADC_TAG, "The driver is already stopped");
return ESP_ERR_INVALID_STATE;
}
s_adc_digi_ctx->driver_start_flag = 0;
//disable the in suc eof intrrupt
adc_hal_digi_dis_intr(&s_adc_digi_ctx->hal, IN_SUC_EOF_BIT);
//clear the in suc eof interrupt
adc_hal_digi_clr_intr(&s_adc_digi_ctx->hal, IN_SUC_EOF_BIT);
//stop ADC
adc_hal_digi_stop(&s_adc_digi_ctx->hal);
//stop DMA
adc_hal_digi_rxdma_stop(&s_adc_digi_ctx->hal);
adc_hal_digi_deinit();
#if CONFIG_PM_ENABLE
if (s_adc_digi_ctx->pm_lock) {
esp_pm_lock_release(s_adc_digi_ctx->pm_lock);
}
#endif //CONFIG_PM_ENABLE
if (s_adc_digi_ctx->use_adc1) {
SAR_ADC1_LOCK_RELEASE();
}
if (s_adc_digi_ctx->use_adc2) {
SAR_ADC2_LOCK_RELEASE();
}
adc_power_release();
return ESP_OK;
}
esp_err_t adc_digi_read_bytes(uint8_t *buf, uint32_t length_max, uint32_t *out_length, uint32_t timeout_ms)
{
TickType_t ticks_to_wait;
esp_err_t ret = ESP_OK;
uint8_t *data = NULL;
size_t size = 0;
ticks_to_wait = timeout_ms / portTICK_RATE_MS;
if (timeout_ms == ADC_MAX_DELAY) {
ticks_to_wait = portMAX_DELAY;
}
data = xRingbufferReceiveUpTo(s_adc_digi_ctx->ringbuf_hdl, &size, ticks_to_wait, length_max);
if (!data) {
ESP_LOGV(ADC_TAG, "No data, increase timeout or reduce conv_num_each_intr");
ret = ESP_ERR_TIMEOUT;
*out_length = 0;
return ret;
}
memcpy(buf, data, size);
vRingbufferReturnItem(s_adc_digi_ctx->ringbuf_hdl, data);
assert((size % 4) == 0);
*out_length = size;
if (s_adc_digi_ctx->ringbuf_overflow_flag) {
ret = ESP_ERR_INVALID_STATE;
}
return ret;
}
esp_err_t adc_digi_deinitialize(void)
{
if (!s_adc_digi_ctx) {
return ESP_ERR_INVALID_STATE;
}
if (s_adc_digi_ctx->driver_start_flag != 0) {
ESP_LOGE(ADC_TAG, "The driver is not stopped");
return ESP_ERR_INVALID_STATE;
}
if (s_adc_digi_ctx->ringbuf_hdl) {
vRingbufferDelete(s_adc_digi_ctx->ringbuf_hdl);
s_adc_digi_ctx->ringbuf_hdl = NULL;
}
#if CONFIG_PM_ENABLE
if (s_adc_digi_ctx->pm_lock) {
esp_pm_lock_delete(s_adc_digi_ctx->pm_lock);
}
#endif //CONFIG_PM_ENABLE
free(s_adc_digi_ctx->rx_dma_buf);
free(s_adc_digi_ctx->hal.rx_desc);
free(s_adc_digi_ctx->digi_controller_config.adc_pattern);
gdma_disconnect(s_adc_digi_ctx->rx_dma_channel);
gdma_del_channel(s_adc_digi_ctx->rx_dma_channel);
free(s_adc_digi_ctx);
s_adc_digi_ctx = NULL;
periph_module_disable(PERIPH_SARADC_MODULE);
return ESP_OK;
}
/*---------------------------------------------------------------
ADC Single Read Mode
---------------------------------------------------------------*/
static adc_atten_t s_atten1_single[ADC1_CHANNEL_MAX]; //Array saving attenuate of each channel of ADC1, used by single read API
static adc_atten_t s_atten2_single[ADC2_CHANNEL_MAX]; //Array saving attenuate of each channel of ADC2, used by single read API
esp_err_t adc_vref_to_gpio(adc_unit_t adc_unit, gpio_num_t gpio)
{
esp_err_t ret;
uint32_t channel = ADC2_CHANNEL_MAX;
if (adc_unit == ADC_UNIT_2) {
for (int i = 0; i < ADC2_CHANNEL_MAX; i++) {
if (gpio == ADC_GET_IO_NUM(ADC_NUM_2, i)) {
channel = i;
break;
}
}
if (channel == ADC2_CHANNEL_MAX) {
return ESP_ERR_INVALID_ARG;
}
}
adc_power_acquire();
if (adc_unit & ADC_UNIT_1) {
ADC_ENTER_CRITICAL();
adc_hal_vref_output(ADC_NUM_1, channel, true);
ADC_EXIT_CRITICAL()
} else if (adc_unit & ADC_UNIT_2) {
ADC_ENTER_CRITICAL();
adc_hal_vref_output(ADC_NUM_2, channel, true);
ADC_EXIT_CRITICAL()
}
ret = adc_digi_gpio_init(ADC_NUM_2, BIT(channel));
return ret;
}
esp_err_t adc1_config_width(adc_bits_width_t width_bit)
{
//On ESP32C3, the data width is always 12-bits.
if (width_bit != ADC_WIDTH_BIT_12) {
return ESP_ERR_INVALID_ARG;
}
return ESP_OK;
}
esp_err_t adc1_config_channel_atten(adc1_channel_t channel, adc_atten_t atten)
{
ADC_CHANNEL_CHECK(ADC_NUM_1, channel);
ADC_CHECK(atten < ADC_ATTEN_MAX, "ADC Atten Err", ESP_ERR_INVALID_ARG);
esp_err_t ret = ESP_OK;
s_atten1_single[channel] = atten;
ret = adc_digi_gpio_init(ADC_NUM_1, BIT(channel));
adc_hal_calibration_init(ADC_NUM_1);
return ret;
}
int adc1_get_raw(adc1_channel_t channel)
{
int raw_out = 0;
periph_module_enable(PERIPH_SARADC_MODULE);
adc_power_acquire();
SAR_ADC1_LOCK_ACQUIRE();
adc_atten_t atten = s_atten1_single[channel];
uint32_t cal_val = adc_get_calibration_offset(ADC_NUM_1, channel, atten);
adc_hal_set_calibration_param(ADC_NUM_1, cal_val);
ADC_REG_LOCK_ENTER();
adc_hal_set_atten(ADC_NUM_2, channel, atten);
adc_hal_convert(ADC_NUM_1, channel, &raw_out);
ADC_REG_LOCK_EXIT();
SAR_ADC1_LOCK_RELEASE();
adc_power_release();
periph_module_disable(PERIPH_SARADC_MODULE);
return raw_out;
}
esp_err_t adc2_config_channel_atten(adc2_channel_t channel, adc_atten_t atten)
{
ADC_CHANNEL_CHECK(ADC_NUM_2, channel);
ADC_CHECK(atten <= ADC_ATTEN_11db, "ADC2 Atten Err", ESP_ERR_INVALID_ARG);
esp_err_t ret = ESP_OK;
s_atten2_single[channel] = atten;
ret = adc_digi_gpio_init(ADC_NUM_2, BIT(channel));
adc_hal_calibration_init(ADC_NUM_2);
return ret;
}
esp_err_t adc2_get_raw(adc2_channel_t channel, adc_bits_width_t width_bit, int *raw_out)
{
//On ESP32C3, the data width is always 12-bits.
if (width_bit != ADC_WIDTH_BIT_12) {
return ESP_ERR_INVALID_ARG;
}
esp_err_t ret = ESP_OK;
periph_module_enable(PERIPH_SARADC_MODULE);
adc_power_acquire();
SAR_ADC2_LOCK_ACQUIRE();
adc_atten_t atten = s_atten2_single[channel];
uint32_t cal_val = adc_get_calibration_offset(ADC_NUM_2, channel, atten);
adc_hal_set_calibration_param(ADC_NUM_2, cal_val);
ADC_REG_LOCK_ENTER();
adc_hal_set_atten(ADC_NUM_2, channel, atten);
ret = adc_hal_convert(ADC_NUM_2, channel, raw_out);
ADC_REG_LOCK_EXIT();
SAR_ADC2_LOCK_RELEASE();
adc_power_release();
periph_module_disable(PERIPH_SARADC_MODULE);
return ret;
}
/*---------------------------------------------------------------
Digital controller setting
---------------------------------------------------------------*/
esp_err_t adc_digi_controller_config(const adc_digi_config_t *config)
{
if (!s_adc_digi_ctx) {
return ESP_ERR_INVALID_STATE;
}
ADC_CHECK(config->sample_freq_hz <= SOC_ADC_SAMPLE_FREQ_THRES_HIGH && config->sample_freq_hz >= SOC_ADC_SAMPLE_FREQ_THRES_LOW, "ADC sampling frequency out of range", ESP_ERR_INVALID_ARG);
s_adc_digi_ctx->digi_controller_config.conv_limit_en = config->conv_limit_en;
s_adc_digi_ctx->digi_controller_config.conv_limit_num = config->conv_limit_num;
s_adc_digi_ctx->digi_controller_config.adc_pattern_len = config->adc_pattern_len;
s_adc_digi_ctx->digi_controller_config.sample_freq_hz = config->sample_freq_hz;
memcpy(s_adc_digi_ctx->digi_controller_config.adc_pattern, config->adc_pattern, config->adc_pattern_len * sizeof(adc_digi_pattern_table_t));
const int atten_uninitialised = 999;
s_adc_digi_ctx->adc1_atten = atten_uninitialised;
s_adc_digi_ctx->adc2_atten = atten_uninitialised;
s_adc_digi_ctx->use_adc1 = 0;
s_adc_digi_ctx->use_adc2 = 0;
for (int i = 0; i < config->adc_pattern_len; i++) {
const adc_digi_pattern_table_t *pat = &config->adc_pattern[i];
if (pat->unit == ADC_NUM_1) {
s_adc_digi_ctx->use_adc1 = 1;
if (s_adc_digi_ctx->adc1_atten == atten_uninitialised) {
s_adc_digi_ctx->adc1_atten = pat->atten;
} else if (s_adc_digi_ctx->adc1_atten != pat->atten) {
return ESP_ERR_INVALID_ARG;
}
} else if (pat->unit == ADC_NUM_2) {
//See whether ADC2 will be used or not. If yes, the ``sar_adc2_mutex`` should be acquired in the continuous read driver
s_adc_digi_ctx->use_adc2 = 1;
if (s_adc_digi_ctx->adc2_atten == atten_uninitialised) {
s_adc_digi_ctx->adc2_atten = pat->atten;
} else if (s_adc_digi_ctx->adc2_atten != pat->atten) {
return ESP_ERR_INVALID_ARG;
}
}
}
return ESP_OK;
}
/*************************************/
/* Digital controller filter setting */
/*************************************/
esp_err_t adc_digi_filter_reset(adc_digi_filter_idx_t idx)
{
ADC_ENTER_CRITICAL();
adc_hal_digi_filter_reset(idx);
ADC_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t adc_digi_filter_set_config(adc_digi_filter_idx_t idx, adc_digi_filter_t *config)
{
ADC_ENTER_CRITICAL();
adc_hal_digi_filter_set_factor(idx, config);
ADC_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t adc_digi_filter_get_config(adc_digi_filter_idx_t idx, adc_digi_filter_t *config)
{
ADC_ENTER_CRITICAL();
adc_hal_digi_filter_get_factor(idx, config);
ADC_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t adc_digi_filter_enable(adc_digi_filter_idx_t idx, bool enable)
{
ADC_ENTER_CRITICAL();
adc_hal_digi_filter_enable(idx, enable);
ADC_EXIT_CRITICAL();
return ESP_OK;
}
/**************************************/
/* Digital controller monitor setting */
/**************************************/
esp_err_t adc_digi_monitor_set_config(adc_digi_monitor_idx_t idx, adc_digi_monitor_t *config)
{
ADC_ENTER_CRITICAL();
adc_hal_digi_monitor_config(idx, config);
ADC_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t adc_digi_monitor_enable(adc_digi_monitor_idx_t idx, bool enable)
{
ADC_ENTER_CRITICAL();
adc_hal_digi_monitor_enable(idx, enable);
ADC_EXIT_CRITICAL();
return ESP_OK;
}
/*---------------------------------------------------------------
RTC controller setting
---------------------------------------------------------------*/
static uint16_t s_adc_cali_param[ADC_UNIT_MAX][ADC_ATTEN_MAX] = {};
//NOTE: according to calibration version, different types of lock may be taken during the process:
// 1. Semaphore when reading efuse
// 2. Lock (Spinlock, or Mutex) if we actually do ADC calibration in the future
//This function shoudn't be called inside critical section or ISR
static uint32_t adc_get_calibration_offset(adc_ll_num_t adc_n, adc_channel_t channel, adc_atten_t atten)
{
const bool no_cal = false;
if (s_adc_cali_param[adc_n][atten]) {
return (uint32_t)s_adc_cali_param[adc_n][atten];
}
if (no_cal) {
return 0; //indicating failure
}
// check if we can fetch the values from eFuse.
int version = esp_efuse_rtc_calib_get_ver();
uint32_t init_code = 0;
if (version == 1) {
//for calibration v1, both ADC units use the same init code (calibrated by ADC1)
init_code = esp_efuse_rtc_calib_get_init_code(version, atten);
ESP_LOGD(ADC_TAG, "Calib(V%d) ADC0, 1 atten=%d: %04X", version, atten, init_code);
s_adc_cali_param[0][atten] = init_code;
s_adc_cali_param[1][atten] = init_code;
} else {
adc_power_acquire();
ADC_ENTER_CRITICAL();
const bool internal_gnd = true;
init_code = adc_hal_self_calibration(adc_n, channel, atten, internal_gnd);
ADC_EXIT_CRITICAL();
adc_power_release();
ESP_LOGD(ADC_TAG, "Calib(V%d) ADC%d atten=%d: %04X", version, adc_n, atten, init_code);
s_adc_cali_param[adc_n][atten] = init_code;
}
return init_code;
}
// Internal function to calibrate PWDET for WiFi
esp_err_t adc_cal_offset(adc_ll_num_t adc_n, adc_channel_t channel, adc_atten_t atten)
{
adc_hal_calibration_init(adc_n);
uint32_t cal_val = adc_get_calibration_offset(adc_n, channel, atten);
ADC_ENTER_CRITICAL();
adc_hal_set_calibration_param(adc_n, cal_val);
ADC_EXIT_CRITICAL();
return ESP_OK;
}

View File

@ -0,0 +1,31 @@
/*
* SPDX-FileCopyrightText: 2016-2021 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
/* This file is used to get `adc2_init_code_calibration` executed before the APP when the ADC2 is used by Wi-Fi or other drivers.
The linker will link constructor (adc2_init_code_calibration) only when any sections inside the same file (adc2_cal_include) is used.
Don't put any other code into this file. */
#include "adc2_wifi_private.h"
#include "hal/adc_hal.h"
#include "esp_private/adc_cali.h"
/**
* @brief Set initial code to ADC2 after calibration. ADC2 RTC and ADC2 PWDET controller share the initial code.
* This API be called in before `app_main()`.
*/
static __attribute__((constructor)) void adc2_init_code_calibration(void)
{
const adc_ll_num_t adc_n = ADC_NUM_2;
const adc_atten_t atten = ADC_ATTEN_DB_11;
const adc_channel_t channel = 0;
adc_cal_offset(adc_n, channel, atten);
}
/** Don't call `adc2_cal_include` in user code. */
void adc2_cal_include(void)
{
/* When this empty function is called, the `adc2_init_code_calibration` constructor will be linked and executed before the app.*/
}

View File

@ -0,0 +1,93 @@
/*
* SPDX-FileCopyrightText: 2019-2021 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once
#include "driver/adc_common.h"
#ifdef __cplusplus
extern "C" {
#endif
/*---------------------------------------------------------------
Common setting
---------------------------------------------------------------*/
/*************************************/
/* Digital controller filter setting */
/*************************************/
/**
* @brief Reset adc digital controller filter.
*
* @param idx Filter index.
*
* @return
* - ESP_OK Success
*/
esp_err_t adc_digi_filter_reset(adc_digi_filter_idx_t idx);
/**
* @brief Set adc digital controller filter configuration.
*
* @param idx Filter index.
* @param config See ``adc_digi_filter_t``.
*
* @return
* - ESP_OK Success
*/
esp_err_t adc_digi_filter_set_config(adc_digi_filter_idx_t idx, adc_digi_filter_t *config);
/**
* @brief Get adc digital controller filter configuration.
*
* @param idx Filter index.
* @param config See ``adc_digi_filter_t``.
*
* @return
* - ESP_OK Success
*/
esp_err_t adc_digi_filter_get_config(adc_digi_filter_idx_t idx, adc_digi_filter_t *config);
/**
* @brief Enable/disable adc digital controller filter.
* Filtering the ADC data to obtain smooth data at higher sampling rates.
*
* @param idx Filter index.
* @param enable Enable/Disable filter.
*
* @return
* - ESP_OK Success
*/
esp_err_t adc_digi_filter_enable(adc_digi_filter_idx_t idx, bool enable);
/**************************************/
/* Digital controller monitor setting */
/**************************************/
/**
* @brief Config monitor of adc digital controller.
*
* @param idx Monitor index.
* @param config See ``adc_digi_monitor_t``.
*
* @return
* - ESP_OK Success
*/
esp_err_t adc_digi_monitor_set_config(adc_digi_monitor_idx_t idx, adc_digi_monitor_t *config);
/**
* @brief Enable/disable monitor of adc digital controller.
*
* @param idx Monitor index.
* @param enable True or false enable monitor.
*
* @return
* - ESP_OK Success
*/
esp_err_t adc_digi_monitor_enable(adc_digi_monitor_idx_t idx, bool enable);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,91 @@
/*
* SPDX-FileCopyrightText: 2010-2021 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once
#include <stdint.h>
#include "esp_err.h"
#ifdef __cplusplus
extern "C" {
#endif
typedef enum {
TSENS_DAC_L0 = 0, /*!< offset = -2, measure range: 50℃ ~ 125℃, error < 3℃. */
TSENS_DAC_L1, /*!< offset = -1, measure range: 20℃ ~ 100℃, error < 2℃. */
TSENS_DAC_L2, /*!< offset = 0, measure range:-10℃ ~ 80℃, error < 1℃. */
TSENS_DAC_L3, /*!< offset = 1, measure range:-30℃ ~ 50℃, error < 2℃. */
TSENS_DAC_L4, /*!< offset = 2, measure range:-40℃ ~ 20℃, error < 3℃. */
TSENS_DAC_MAX,
TSENS_DAC_DEFAULT = TSENS_DAC_L2,
} temp_sensor_dac_offset_t;
/**
* @brief Configuration for temperature sensor reading
*/
typedef struct {
temp_sensor_dac_offset_t dac_offset; /*!< The temperature measurement range is configured with a built-in temperature offset DAC. */
uint8_t clk_div; /*!< Default: 6 */
} temp_sensor_config_t;
#define TSENS_CONFIG_DEFAULT() {.dac_offset = TSENS_DAC_L2, \
.clk_div = 6}
/**
* @brief Set parameter of temperature sensor.
* @param tsens
* @return
* - ESP_OK Success
*/
esp_err_t temp_sensor_set_config(temp_sensor_config_t tsens);
/**
* @brief Get parameter of temperature sensor.
* @param tsens
* @return
* - ESP_OK Success
*/
esp_err_t temp_sensor_get_config(temp_sensor_config_t *tsens);
/**
* @brief Start temperature sensor measure.
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG
*/
esp_err_t temp_sensor_start(void);
/**
* @brief Stop temperature sensor measure.
* @return
* - ESP_OK Success
*/
esp_err_t temp_sensor_stop(void);
/**
* @brief Read temperature sensor raw data.
* @param tsens_out Pointer to raw data, Range: 0 ~ 255
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG `tsens_out` is NULL
* - ESP_ERR_INVALID_STATE temperature sensor dont start
*/
esp_err_t temp_sensor_read_raw(uint32_t *tsens_out);
/**
* @brief Read temperature sensor data that is converted to degrees Celsius.
* @note Should not be called from interrupt.
* @param celsius The measure output value.
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG ARG is NULL.
* - ESP_ERR_INVALID_STATE The ambient temperature is out of range.
*/
esp_err_t temp_sensor_read_celsius(float *celsius);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,151 @@
/*
* SPDX-FileCopyrightText: 2016-2021 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <esp_types.h>
#include <stdlib.h>
#include <ctype.h>
#include <math.h>
#include "freertos/FreeRTOS.h"
#include "freertos/semphr.h"
#include "esp_log.h"
#include "hal/adc_ll.h"
#include "soc/rtc_cntl_reg.h"
#include "soc/apb_saradc_struct.h"
#include "soc/apb_saradc_reg.h"
#include "soc/system_reg.h"
#include "driver/temp_sensor.h"
#include "regi2c_ctrl.h"
#include "esp32c3/rom/ets_sys.h"
#include "esp_efuse_rtc_calib.h"
static const char *TAG = "tsens";
#define TSENS_CHECK(res, ret_val) ({ \
if (!(res)) { \
ESP_LOGE(TAG, "%s(%d)", __FUNCTION__, __LINE__); \
return (ret_val); \
} \
})
#define TSENS_XPD_WAIT_DEFAULT 0xFF /* Set wait cycle time(8MHz) from power up to reset enable. */
#define TSENS_ADC_FACTOR (0.4386)
#define TSENS_DAC_FACTOR (27.88)
#define TSENS_SYS_OFFSET (20.52)
typedef struct {
int index;
int offset;
int set_val;
int range_min;
int range_max;
int error_max;
} tsens_dac_offset_t;
static const tsens_dac_offset_t dac_offset[TSENS_DAC_MAX] = {
/* DAC Offset reg_val min max error */
{TSENS_DAC_L0, -2, 5, 50, 125, 3},
{TSENS_DAC_L1, -1, 7, 20, 100, 2},
{TSENS_DAC_L2, 0, 15, -10, 80, 1},
{TSENS_DAC_L3, 1, 11, -30, 50, 2},
{TSENS_DAC_L4, 2, 10, -40, 20, 3},
};
static float s_deltaT = NAN; // unused number
esp_err_t temp_sensor_set_config(temp_sensor_config_t tsens)
{
REG_SET_BIT(SYSTEM_PERIP_CLK_EN1_REG, SYSTEM_TSENS_CLK_EN);
CLEAR_PERI_REG_MASK(ANA_CONFIG_REG, ANA_I2C_SAR_FORCE_PD);
SET_PERI_REG_MASK(ANA_CONFIG2_REG, ANA_I2C_SAR_FORCE_PU);
REGI2C_WRITE_MASK(I2C_SAR_ADC, I2C_SARADC_TSENS_DAC, dac_offset[tsens.dac_offset].set_val);
APB_SARADC.apb_tsens_ctrl.tsens_clk_div = tsens.clk_div;
APB_SARADC.apb_tsens_ctrl2.tsens_xpd_wait = TSENS_XPD_WAIT_DEFAULT;
APB_SARADC.apb_tsens_ctrl2.tsens_xpd_force = 1;
ESP_LOGD(TAG, "Config temperature range [%d°C ~ %d°C], error < %d°C",
dac_offset[tsens.dac_offset].range_min,
dac_offset[tsens.dac_offset].range_max,
dac_offset[tsens.dac_offset].error_max);
return ESP_OK;
}
esp_err_t temp_sensor_get_config(temp_sensor_config_t *tsens)
{
TSENS_CHECK(tsens != NULL, ESP_ERR_INVALID_ARG);
CLEAR_PERI_REG_MASK(ANA_CONFIG_REG, ANA_I2C_SAR_FORCE_PD);
SET_PERI_REG_MASK(ANA_CONFIG2_REG, ANA_I2C_SAR_FORCE_PU);
tsens->dac_offset = REGI2C_READ_MASK(I2C_SAR_ADC, I2C_SARADC_TSENS_DAC);
for (int i = TSENS_DAC_L0; i < TSENS_DAC_MAX; i++) {
if (tsens->dac_offset == dac_offset[i].set_val) {
tsens->dac_offset = dac_offset[i].index;
break;
}
}
tsens->clk_div = APB_SARADC.apb_tsens_ctrl.tsens_clk_div;
return ESP_OK;
}
esp_err_t temp_sensor_start(void)
{
REG_SET_BIT(SYSTEM_PERIP_CLK_EN1_REG, SYSTEM_TSENS_CLK_EN);
APB_SARADC.apb_tsens_ctrl2.tsens_clk_sel = 1;
APB_SARADC.apb_tsens_ctrl.tsens_pu = 1;
return ESP_OK;
}
esp_err_t temp_sensor_stop(void)
{
APB_SARADC.apb_tsens_ctrl.tsens_pu = 0;
APB_SARADC.apb_tsens_ctrl2.tsens_clk_sel = 0;
return ESP_OK;
}
esp_err_t temp_sensor_read_raw(uint32_t *tsens_out)
{
TSENS_CHECK(tsens_out != NULL, ESP_ERR_INVALID_ARG);
*tsens_out = APB_SARADC.apb_tsens_ctrl.tsens_out;
return ESP_OK;
}
static void read_delta_t_from_efuse(void)
{
uint32_t version = esp_efuse_rtc_calib_get_ver();
if (version == 1) {
// fetch calibration value for temp sensor from eFuse
s_deltaT = esp_efuse_rtc_calib_get_cal_temp(version);
} else {
// no value to fetch, use 0.
s_deltaT = 0;
}
ESP_LOGD(TAG, "s_deltaT = %f", s_deltaT);
}
static float parse_temp_sensor_raw_value(uint32_t tsens_raw, const int dac_offset)
{
if (isnan(s_deltaT)) { //suggests that the value is not initialized
read_delta_t_from_efuse();
}
float result = (TSENS_ADC_FACTOR * (float)tsens_raw - TSENS_DAC_FACTOR * dac_offset - TSENS_SYS_OFFSET) - s_deltaT / 10.0;
return result;
}
esp_err_t temp_sensor_read_celsius(float *celsius)
{
TSENS_CHECK(celsius != NULL, ESP_ERR_INVALID_ARG);
temp_sensor_config_t tsens;
uint32_t tsens_out = 0;
esp_err_t ret = temp_sensor_get_config(&tsens);
if (ret == ESP_OK) {
ret = temp_sensor_read_raw(&tsens_out);
printf("tsens_out %d\r\n", tsens_out);
TSENS_CHECK(ret == ESP_OK, ret);
const tsens_dac_offset_t *dac = &dac_offset[tsens.dac_offset];
*celsius = parse_temp_sensor_raw_value(tsens_out, dac->offset);
if (*celsius < dac->range_min || *celsius > dac->range_max) {
ESP_LOGW(TAG, "Exceeding the temperature range!");
ret = ESP_ERR_INVALID_STATE;
}
}
return ret;
}

View File

@ -0,0 +1,66 @@
idf_build_get_property(target IDF_TARGET)
idf_build_get_property(sdkconfig_header SDKCONFIG_HEADER)
if(NOT "${target}" STREQUAL "esp32c3")
return()
endif()
if(BOOTLOADER_BUILD)
# For bootloader, all we need from esp32c3 is headers
idf_component_register(INCLUDE_DIRS include REQUIRES riscv)
target_linker_script(${COMPONENT_LIB} INTERFACE "ld/esp32c3.peripherals.ld")
else()
# Regular app build
set(srcs "dport_access.c"
"esp_hmac.c"
"esp_ds.c"
"esp_crypto_lock.c"
"memprot.c")
set(include_dirs "include")
set(requires driver efuse soc riscv) #unfortunately rom/uart uses SOC registers directly
# driver is a public requirement because esp_sleep.h uses gpio_num_t & touch_pad_t
# app_update is added here because cpu_start.c uses esp_ota_get_app_description() function.
# esp_timer is added here because cpu_start.c uses esp_timer
set(priv_requires
app_trace app_update bootloader_support log mbedtls nvs_flash
pthread spi_flash vfs espcoredump esp_common esp_timer)
idf_component_register(SRCS "${srcs}"
INCLUDE_DIRS "${include_dirs}"
REQUIRES "${requires}"
PRIV_REQUIRES "${priv_requires}"
REQUIRED_IDF_TARGETS esp32c3)
target_linker_script(${COMPONENT_LIB} INTERFACE "${CMAKE_CURRENT_BINARY_DIR}/esp32c3_out.ld")
# Process the template file through the linker script generation mechanism, and use the output for linking the
# final binary
target_linker_script(${COMPONENT_LIB} INTERFACE "${CMAKE_CURRENT_LIST_DIR}/ld/esp32c3.project.ld.in"
PROCESS "${CMAKE_CURRENT_BINARY_DIR}/ld/esp32c3.project.ld")
target_linker_script(${COMPONENT_LIB} INTERFACE "ld/esp32c3.peripherals.ld")
target_link_libraries(${COMPONENT_LIB} PUBLIC gcc)
target_link_libraries(${COMPONENT_LIB} INTERFACE "-u call_user_start_cpu0")
idf_build_get_property(config_dir CONFIG_DIR)
# Preprocess esp32c3.ld linker script to include configuration, becomes esp32c3_out.ld
set(LD_DIR ${CMAKE_CURRENT_SOURCE_DIR}/ld)
add_custom_command(
OUTPUT esp32c3_out.ld
COMMAND "${CMAKE_C_COMPILER}" -C -P -x c -E -o esp32c3_out.ld -I ${config_dir} ${LD_DIR}/esp32c3.ld
MAIN_DEPENDENCY ${LD_DIR}/esp32c3.ld
DEPENDS ${sdkconfig_header}
COMMENT "Generating linker script..."
VERBATIM)
add_custom_target(esp32c3_linker_script DEPENDS ${CMAKE_CURRENT_BINARY_DIR}/esp32c3_out.ld)
add_dependencies(${COMPONENT_LIB} esp32c3_linker_script)
# disable stack protection in files which are involved in initialization of that feature
set_source_files_properties(
cpu_start.c
PROPERTIES COMPILE_FLAGS
-fno-stack-protector)
endif()

212
components/esp32h2/Kconfig Normal file
View File

@ -0,0 +1,212 @@
menu "ESP32C3-Specific"
visible if IDF_TARGET_ESP32C3
choice ESP32C3_DEFAULT_CPU_FREQ_MHZ
prompt "CPU frequency"
default ESP32C3_DEFAULT_CPU_FREQ_40 if IDF_ENV_FPGA
default ESP32C3_DEFAULT_CPU_FREQ_160 if !IDF_ENV_FPGA
help
CPU frequency to be set on application startup.
config ESP32C3_DEFAULT_CPU_FREQ_40
bool "40 MHz"
depends on IDF_ENV_FPGA
config ESP32C3_DEFAULT_CPU_FREQ_80
bool "80 MHz"
config ESP32C3_DEFAULT_CPU_FREQ_160
bool "160 MHz"
endchoice
config ESP32C3_DEFAULT_CPU_FREQ_MHZ
int
default 40 if ESP32C3_DEFAULT_CPU_FREQ_40
default 80 if ESP32C3_DEFAULT_CPU_FREQ_80
default 160 if ESP32C3_DEFAULT_CPU_FREQ_160
choice ESP32C3_REV_MIN
prompt "Minimum Supported ESP32-C3 Revision"
default ESP32C3_REV_MIN_3
help
Minimum revision that ESP-IDF would support.
Only supporting higher chip revisions can reduce binary size.
config ESP32C3_REV_MIN_0
bool "Rev 0"
config ESP32C3_REV_MIN_1
bool "Rev 1"
config ESP32C3_REV_MIN_2
bool "Rev 2"
config ESP32C3_REV_MIN_3
bool "Rev 3"
endchoice
config ESP32C3_REV_MIN
int
default 0 if ESP32C3_REV_MIN_0
default 1 if ESP32C3_REV_MIN_1
default 2 if ESP32C3_REV_MIN_2
default 3 if ESP32C3_REV_MIN_3
config ESP32C3_DEBUG_OCDAWARE
bool "Make exception and panic handlers JTAG/OCD aware"
default y
select FREERTOS_DEBUG_OCDAWARE
help
The FreeRTOS panic and unhandled exception handers can detect a JTAG OCD debugger and
instead of panicking, have the debugger stop on the offending instruction.
config ESP32C3_DEBUG_STUBS_ENABLE
bool "OpenOCD debug stubs"
default COMPILER_OPTIMIZATION_LEVEL_DEBUG
depends on !ESP32C3_TRAX
help
Debug stubs are used by OpenOCD to execute pre-compiled onboard code which does some useful debugging,
e.g. GCOV data dump.
config ESP32C3_BROWNOUT_DET
bool "Hardware brownout detect & reset"
default y
help
The ESP32-C3 has a built-in brownout detector which can detect if the voltage is lower than
a specific value. If this happens, it will reset the chip in order to prevent unintended
behaviour.
choice ESP32C3_BROWNOUT_DET_LVL_SEL
prompt "Brownout voltage level"
depends on ESP32C3_BROWNOUT_DET
default ESP32C3_BROWNOUT_DET_LVL_SEL_7
help
The brownout detector will reset the chip when the supply voltage is approximately
below this level. Note that there may be some variation of brownout voltage level
between each chip.
#The voltage levels here are estimates, more work needs to be done to figure out the exact voltages
#of the brownout threshold levels.
config ESP32C3_BROWNOUT_DET_LVL_SEL_7
bool "2.51V"
config ESP32C3_BROWNOUT_DET_LVL_SEL_6
bool "2.64V"
config ESP32C3_BROWNOUT_DET_LVL_SEL_5
bool "2.76V"
config ESP32C3_BROWNOUT_DET_LVL_SEL_4
bool "2.92V"
config ESP32C3_BROWNOUT_DET_LVL_SEL_3
bool "3.10V"
config ESP32C3_BROWNOUT_DET_LVL_SEL_2
bool "3.27V"
endchoice
config ESP32C3_BROWNOUT_DET_LVL
int
default 2 if ESP32C3_BROWNOUT_DET_LVL_SEL_2
default 3 if ESP32C3_BROWNOUT_DET_LVL_SEL_3
default 4 if ESP32C3_BROWNOUT_DET_LVL_SEL_4
default 5 if ESP32C3_BROWNOUT_DET_LVL_SEL_5
default 6 if ESP32C3_BROWNOUT_DET_LVL_SEL_6
default 7 if ESP32C3_BROWNOUT_DET_LVL_SEL_7
choice ESP32C3_TIME_SYSCALL
prompt "Timers used for gettimeofday function"
default ESP32C3_TIME_SYSCALL_USE_RTC_SYSTIMER
help
This setting defines which hardware timers are used to
implement 'gettimeofday' and 'time' functions in C library.
- If both high-resolution (systimer) and RTC timers are used, timekeeping will
continue in deep sleep. Time will be reported at 1 microsecond
resolution. This is the default, and the recommended option.
- If only high-resolution timer (systimer) is used, gettimeofday will
provide time at microsecond resolution.
Time will not be preserved when going into deep sleep mode.
- If only RTC timer is used, timekeeping will continue in
deep sleep, but time will be measured at 6.(6) microsecond
resolution. Also the gettimeofday function itself may take
longer to run.
- If no timers are used, gettimeofday and time functions
return -1 and set errno to ENOSYS.
- When RTC is used for timekeeping, two RTC_STORE registers are
used to keep time in deep sleep mode.
config ESP32C3_TIME_SYSCALL_USE_RTC_SYSTIMER
bool "RTC and high-resolution timer"
select ESP_TIME_FUNCS_USE_RTC_TIMER
select ESP_TIME_FUNCS_USE_ESP_TIMER
config ESP32C3_TIME_SYSCALL_USE_RTC
bool "RTC"
select ESP_TIME_FUNCS_USE_RTC_TIMER
config ESP32C3_TIME_SYSCALL_USE_SYSTIMER
bool "High-resolution timer"
select ESP_TIME_FUNCS_USE_ESP_TIMER
config ESP32C3_TIME_SYSCALL_USE_NONE
bool "None"
select ESP_TIME_FUNCS_USE_NONE
endchoice
choice ESP32C3_RTC_CLK_SRC
prompt "RTC clock source"
default ESP32C3_RTC_CLK_SRC_INT_RC
help
Choose which clock is used as RTC clock source.
config ESP32C3_RTC_CLK_SRC_INT_RC
bool "Internal 150kHz RC oscillator"
config ESP32C3_RTC_CLK_SRC_EXT_CRYS
bool "External 32kHz crystal"
select ESP_SYSTEM_RTC_EXT_XTAL
config ESP32C3_RTC_CLK_SRC_EXT_OSC
bool "External 32kHz oscillator at 32K_XP pin"
config ESP32C3_RTC_CLK_SRC_INT_8MD256
bool "Internal 8MHz oscillator, divided by 256 (~32kHz)"
endchoice
config ESP32C3_RTC_CLK_CAL_CYCLES
int "Number of cycles for RTC_SLOW_CLK calibration"
default 3000 if ESP32C3_RTC_CLK_SRC_EXT_CRYS || ESP32C3_RTC_CLK_SRC_EXT_OSC || ESP32C3_RTC_CLK_SRC_INT_8MD256
default 1024 if ESP32C3_RTC_CLK_SRC_INT_RC
range 0 27000 if ESP32C3_RTC_CLK_SRC_EXT_CRYS || ESP32C3_RTC_CLK_SRC_EXT_OSC || ESP32C3_RTC_CLK_SRC_INT_8MD256
range 0 32766 if ESP32C3_RTC_CLK_SRC_INT_RC
help
When the startup code initializes RTC_SLOW_CLK, it can perform
calibration by comparing the RTC_SLOW_CLK frequency with main XTAL
frequency. This option sets the number of RTC_SLOW_CLK cycles measured
by the calibration routine. Higher numbers increase calibration
precision, which may be important for applications which spend a lot of
time in deep sleep. Lower numbers reduce startup time.
When this option is set to 0, clock calibration will not be performed at
startup, and approximate clock frequencies will be assumed:
- 150000 Hz if internal RC oscillator is used as clock source. For this use value 1024.
- 32768 Hz if the 32k crystal oscillator is used. For this use value 3000 or more.
In case more value will help improve the definition of the launch of the crystal.
If the crystal could not start, it will be switched to internal RC.
config ESP32C3_NO_BLOBS
bool "No Binary Blobs"
depends on !BT_ENABLED
default n
help
If enabled, this disables the linking of binary libraries in the application build. Note
that after enabling this Wi-Fi/Bluetooth will not work.
config ESP32C3_LIGHTSLEEP_GPIO_RESET_WORKAROUND
bool "light sleep GPIO reset workaround"
default y
select PM_SLP_DISABLE_GPIO if FREERTOS_USE_TICKLESS_IDLE
help
ESP32C3 will reset at wake-up if GPIO is received a small electrostatic pulse during
light sleep, with specific condition
- GPIO needs to be configured as input-mode only
- The pin receives a small electrostatic pulse, and reset occurs when the pulse
voltage is higher than 6 V
For GPIO set to input mode only, it is not a good practice to leave it open/floating,
The hardware design needs to controlled it with determined supply or ground voltage
is necessary.
This option provides a software workaround for this issue. Configure to isolate all
GPIO pins in sleep state.
endmenu # ESP32C3-Specific

View File

@ -0,0 +1 @@
# ESP32-C3 is not supported in the GNU Make build system.

View File

@ -0,0 +1,4 @@
#
# Component Makefile
#
COMPONENT_CONFIG_ONLY := 1

View File

@ -0,0 +1,25 @@
// Copyright 2010-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 <stdint.h>
#include <string.h>
#include "soc/dport_access.h"
// Read a sequence of DPORT registers to the buffer.
void esp_dport_access_read_buffer(uint32_t *buff_out, uint32_t address, uint32_t num_words)
{
for (uint32_t i = 0; i < num_words; ++i) {
buff_out[i] = DPORT_SEQUENCE_REG_READ(address + i * 4);
}
}

View File

@ -0,0 +1,83 @@
// Copyright 2015-2020 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <sys/lock.h>
#include "esp_crypto_lock.h"
/* Lock overview:
SHA: peripheral independent, but DMA is shared with AES
AES: peripheral independent, but DMA is shared with SHA
MPI/RSA: independent
HMAC: needs SHA
DS: needs HMAC (which needs SHA), AES and MPI
*/
/* Lock for DS peripheral */
static _lock_t s_crypto_ds_lock;
/* Lock for HMAC peripheral */
static _lock_t s_crypto_hmac_lock;
/* Lock for the MPI/RSA peripheral, also used by the DS peripheral */
static _lock_t s_crypto_mpi_lock;
/* Single lock for SHA and AES, sharing a reserved GDMA channel */
static _lock_t s_crypto_sha_aes_lock;
void esp_crypto_hmac_lock_acquire(void)
{
_lock_acquire(&s_crypto_hmac_lock);
esp_crypto_sha_aes_lock_acquire();
}
void esp_crypto_hmac_lock_release(void)
{
esp_crypto_sha_aes_lock_release();
_lock_release(&s_crypto_hmac_lock);
}
void esp_crypto_ds_lock_acquire(void)
{
_lock_acquire(&s_crypto_ds_lock);
esp_crypto_hmac_lock_acquire();
esp_crypto_mpi_lock_acquire();
}
void esp_crypto_ds_lock_release(void)
{
esp_crypto_mpi_lock_release();
esp_crypto_hmac_lock_release();
_lock_release(&s_crypto_ds_lock);
}
void esp_crypto_sha_aes_lock_acquire(void)
{
_lock_acquire(&s_crypto_sha_aes_lock);
}
void esp_crypto_sha_aes_lock_release(void)
{
_lock_release(&s_crypto_sha_aes_lock);
}
void esp_crypto_mpi_lock_acquire(void)
{
_lock_acquire(&s_crypto_mpi_lock);
}
void esp_crypto_mpi_lock_release(void)
{
_lock_release(&s_crypto_mpi_lock);
}

232
components/esp32h2/esp_ds.c Normal file
View File

@ -0,0 +1,232 @@
// 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 <stdlib.h>
#include <string.h>
#include <assert.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "driver/periph_ctrl.h"
#include "esp_crypto_lock.h"
#include "hal/ds_hal.h"
#include "hal/ds_ll.h"
#include "hal/hmac_hal.h"
#include "esp32c3/rom/digital_signature.h"
#include "esp_timer.h"
#include "esp_ds.h"
struct esp_ds_context {
const esp_ds_data_t *data;
};
/**
* The vtask delay \c esp_ds_sign() is using while waiting for completion of the signing operation.
*/
#define ESP_DS_SIGN_TASK_DELAY_MS 10
#define RSA_LEN_MAX 127
/*
* esp_digital_signature_length_t is used in esp_ds_data_t in contrast to ets_ds_data_t, where unsigned is used.
* Check esp_digital_signature_length_t's width here because it's converted to unsigned using raw casts.
*/
_Static_assert(sizeof(esp_digital_signature_length_t) == sizeof(unsigned),
"The size of esp_digital_signature_length_t and unsigned has to be the same");
/*
* esp_ds_data_t is used in the encryption function but casted to ets_ds_data_t.
* Check esp_ds_data_t's width here because it's converted using raw casts.
*/
_Static_assert(sizeof(esp_ds_data_t) == sizeof(ets_ds_data_t),
"The size of esp_ds_data_t and ets_ds_data_t has to be the same");
static void ds_acquire_enable(void)
{
esp_crypto_ds_lock_acquire();
// We also enable SHA and HMAC here. SHA is used by HMAC, HMAC is used by DS.
periph_module_enable(PERIPH_HMAC_MODULE);
periph_module_enable(PERIPH_SHA_MODULE);
periph_module_enable(PERIPH_DS_MODULE);
hmac_hal_start();
}
static void ds_disable_release(void)
{
ds_hal_finish();
periph_module_disable(PERIPH_DS_MODULE);
periph_module_disable(PERIPH_SHA_MODULE);
periph_module_disable(PERIPH_HMAC_MODULE);
esp_crypto_ds_lock_release();
}
esp_err_t esp_ds_sign(const void *message,
const esp_ds_data_t *data,
hmac_key_id_t key_id,
void *signature)
{
// Need to check signature here, otherwise the signature is only checked when the signing has finished and fails
// but the signing isn't uninitialized and the mutex is still locked.
if (!signature) {
return ESP_ERR_INVALID_ARG;
}
esp_ds_context_t *context;
esp_err_t result = esp_ds_start_sign(message, data, key_id, &context);
if (result != ESP_OK) {
return result;
}
while (esp_ds_is_busy())
vTaskDelay(ESP_DS_SIGN_TASK_DELAY_MS / portTICK_PERIOD_MS);
return esp_ds_finish_sign(signature, context);
}
esp_err_t esp_ds_start_sign(const void *message,
const esp_ds_data_t *data,
hmac_key_id_t key_id,
esp_ds_context_t **esp_ds_ctx)
{
if (!message || !data || !esp_ds_ctx) {
return ESP_ERR_INVALID_ARG;
}
if (key_id >= HMAC_KEY_MAX) {
return ESP_ERR_INVALID_ARG;
}
if (!(data->rsa_length == ESP_DS_RSA_1024
|| data->rsa_length == ESP_DS_RSA_2048
|| data->rsa_length == ESP_DS_RSA_3072)) {
return ESP_ERR_INVALID_ARG;
}
ds_acquire_enable();
// initiate hmac
uint32_t conf_error = hmac_hal_configure(HMAC_OUTPUT_DS, key_id);
if (conf_error) {
ds_disable_release();
return ESP32C3_ERR_HW_CRYPTO_DS_HMAC_FAIL;
}
ds_hal_start();
// check encryption key from HMAC
int64_t start_time = esp_timer_get_time();
while (ds_ll_busy() != 0) {
if ((esp_timer_get_time() - start_time) > SOC_DS_KEY_CHECK_MAX_WAIT_US) {
ds_disable_release();
return ESP32C3_ERR_HW_CRYPTO_DS_INVALID_KEY;
}
}
esp_ds_context_t *context = malloc(sizeof(esp_ds_context_t));
if (!context) {
ds_disable_release();
return ESP_ERR_NO_MEM;
}
size_t rsa_len = (data->rsa_length + 1) * 4;
ds_hal_write_private_key_params(data->c);
ds_hal_configure_iv(data->iv);
ds_hal_write_message(message, rsa_len);
// initiate signing
ds_hal_start_sign();
context->data = data;
*esp_ds_ctx = context;
return ESP_OK;
}
bool esp_ds_is_busy(void)
{
return ds_hal_busy();
}
esp_err_t esp_ds_finish_sign(void *signature, esp_ds_context_t *esp_ds_ctx)
{
if (!signature || !esp_ds_ctx) {
return ESP_ERR_INVALID_ARG;
}
const esp_ds_data_t *data = esp_ds_ctx->data;
unsigned rsa_len = (data->rsa_length + 1) * 4;
while (ds_hal_busy()) { }
ds_signature_check_t sig_check_result = ds_hal_read_result((uint8_t*) signature, (size_t) rsa_len);
esp_err_t return_value = ESP_OK;
if (sig_check_result == DS_SIGNATURE_MD_FAIL || sig_check_result == DS_SIGNATURE_PADDING_AND_MD_FAIL) {
return_value = ESP32C3_ERR_HW_CRYPTO_DS_INVALID_DIGEST;
}
if (sig_check_result == DS_SIGNATURE_PADDING_FAIL) {
return_value = ESP32C3_ERR_HW_CRYPTO_DS_INVALID_PADDING;
}
free(esp_ds_ctx);
hmac_hal_clean();
ds_disable_release();
return return_value;
}
esp_err_t esp_ds_encrypt_params(esp_ds_data_t *data,
const void *iv,
const esp_ds_p_data_t *p_data,
const void *key)
{
if (!p_data) {
return ESP_ERR_INVALID_ARG;
}
esp_err_t result = ESP_OK;
esp_crypto_ds_lock_acquire();
periph_module_enable(PERIPH_AES_MODULE);
periph_module_enable(PERIPH_DS_MODULE);
periph_module_enable(PERIPH_SHA_MODULE);
periph_module_enable(PERIPH_HMAC_MODULE);
periph_module_enable(PERIPH_RSA_MODULE);
ets_ds_data_t *ds_data = (ets_ds_data_t*) data;
const ets_ds_p_data_t *ds_plain_data = (const ets_ds_p_data_t*) p_data;
ets_ds_result_t ets_result = ets_ds_encrypt_params(ds_data, iv, ds_plain_data, key, ETS_DS_KEY_HMAC);
if (ets_result == ETS_DS_INVALID_PARAM) {
result = ESP_ERR_INVALID_ARG;
}
periph_module_disable(PERIPH_RSA_MODULE);
periph_module_disable(PERIPH_HMAC_MODULE);
periph_module_disable(PERIPH_SHA_MODULE);
periph_module_disable(PERIPH_DS_MODULE);
periph_module_disable(PERIPH_AES_MODULE);
esp_crypto_ds_lock_release();
return result;
}

View File

@ -0,0 +1,132 @@
// Copyright 2015-2020 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <string.h>
#include "driver/periph_ctrl.h"
#include "esp32c3/rom/hmac.h"
#include "esp32c3/rom/ets_sys.h"
#include "esp_hmac.h"
#include "esp_crypto_lock.h"
#include "hal/hmac_hal.h"
#define SHA256_BLOCK_SZ 64
#define SHA256_PAD_SZ 8
/**
* @brief Apply the HMAC padding without the embedded length.
*
* @note This function does not check the data length, it is the responsibility of the other functions in this
* module to make sure that \c data_len is at most SHA256_BLOCK_SZ - 1 so the padding fits in.
* Otherwise, this function has undefined behavior.
* Note however, that for the actual HMAC implementation on ESP32C3, the length also needs to be applied at the end
* of the block. This function alone deosn't do that.
*/
static void write_and_padd(uint8_t *block, const uint8_t *data, uint16_t data_len)
{
memcpy(block, data, data_len);
// Apply a one bit, followed by zero bits (refer to the ESP32C3 TRM).
block[data_len] = 0x80;
bzero(block + data_len + 1, SHA256_BLOCK_SZ - data_len - 1);
}
esp_err_t esp_hmac_calculate(hmac_key_id_t key_id,
const void *message,
size_t message_len,
uint8_t *hmac)
{
const uint8_t *message_bytes = (const uint8_t *)message;
if (!message || !hmac) {
return ESP_ERR_INVALID_ARG;
}
if (key_id >= HMAC_KEY_MAX) {
return ESP_ERR_INVALID_ARG;
}
esp_crypto_hmac_lock_acquire();
// We also enable SHA and DS here. SHA is used by HMAC, DS will otherwise hold SHA in reset state.
periph_module_enable(PERIPH_HMAC_MODULE);
periph_module_enable(PERIPH_SHA_MODULE);
periph_module_enable(PERIPH_DS_MODULE);
hmac_hal_start();
uint32_t conf_error = hmac_hal_configure(HMAC_OUTPUT_USER, key_id);
if (conf_error) {
esp_crypto_hmac_lock_release();
return ESP_FAIL;
}
if (message_len + 1 + SHA256_PAD_SZ <= SHA256_BLOCK_SZ) {
// If message including padding is only one block...
// Last message block, so apply SHA-256 padding rules in software
uint8_t block[SHA256_BLOCK_SZ];
uint64_t bit_len = __builtin_bswap64(message_len * 8 + 512);
write_and_padd(block, message_bytes, message_len);
// Final block: append the bit length in this block and signal padding to peripheral
memcpy(block + SHA256_BLOCK_SZ - sizeof(bit_len),
&bit_len, sizeof(bit_len));
hmac_hal_write_one_block_512(block);
} else {
// If message including padding is needs more than one block
// write all blocks without padding except the last one
size_t remaining_blocks = message_len / SHA256_BLOCK_SZ;
for (int i = 1; i < remaining_blocks; i++) {
hmac_hal_write_block_512(message_bytes);
message_bytes += SHA256_BLOCK_SZ;
hmac_hal_next_block_normal();
}
// If message fits into one block but without padding, we must not write another block.
if (remaining_blocks) {
hmac_hal_write_block_512(message_bytes);
message_bytes += SHA256_BLOCK_SZ;
}
size_t remaining = message_len % SHA256_BLOCK_SZ;
// Last message block, so apply SHA-256 padding rules in software
uint8_t block[SHA256_BLOCK_SZ];
uint64_t bit_len = __builtin_bswap64(message_len * 8 + 512);
// If the remaining message and appended padding doesn't fit into a single block, we have to write an
// extra block with the rest of the message and potential padding first.
if (remaining >= SHA256_BLOCK_SZ - SHA256_PAD_SZ) {
write_and_padd(block, message_bytes, remaining);
hmac_hal_next_block_normal();
hmac_hal_write_block_512(block);
bzero(block, SHA256_BLOCK_SZ);
} else {
write_and_padd(block, message_bytes, remaining);
}
memcpy(block + SHA256_BLOCK_SZ - sizeof(bit_len),
&bit_len, sizeof(bit_len));
hmac_hal_next_block_padding();
hmac_hal_write_block_512(block);
}
// Read back result (bit swapped)
hmac_hal_read_result_256(hmac);
periph_module_disable(PERIPH_DS_MODULE);
periph_module_disable(PERIPH_SHA_MODULE);
periph_module_disable(PERIPH_HMAC_MODULE);
esp_crypto_hmac_lock_release();
return ESP_OK;
}

View File

@ -0,0 +1,42 @@
// Copyright 2010-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.
#ifndef _ESP_DPORT_ACCESS_H_
#define _ESP_DPORT_ACCESS_H_
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Read a sequence of DPORT registers to the buffer.
*
* @param[out] buff_out Contains the read data.
* @param[in] address Initial address for reading registers.
* @param[in] num_words The number of words.
*/
void esp_dport_access_read_buffer(uint32_t *buff_out, uint32_t address, uint32_t num_words);
#define DPORT_STALL_OTHER_CPU_START()
#define DPORT_STALL_OTHER_CPU_END()
#define DPORT_INTERRUPT_DISABLE()
#define DPORT_INTERRUPT_RESTORE()
#ifdef __cplusplus
}
#endif
#endif /* _ESP_DPORT_ACCESS_H_ */

View File

@ -0,0 +1,455 @@
// 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.
/* INTERNAL API
* generic interface to PMS memory protection features
*/
#pragma once
#include <stdbool.h>
#include "esp_attr.h"
#ifdef __cplusplus
extern "C" {
#endif
#ifndef IRAM_SRAM_START
#define IRAM_SRAM_START 0x4037C000
#endif
#ifndef DRAM_SRAM_START
#define DRAM_SRAM_START 0x3FC7C000
#endif
#ifndef MAP_DRAM_TO_IRAM
#define MAP_DRAM_TO_IRAM(addr) (addr - DRAM_SRAM_START + IRAM_SRAM_START)
#endif
#ifndef MAP_IRAM_TO_DRAM
#define MAP_IRAM_TO_DRAM(addr) (addr - IRAM_SRAM_START + DRAM_SRAM_START)
#endif
typedef enum {
MEMPROT_NONE = 0x00000000,
MEMPROT_IRAM0_SRAM = 0x00000001,
MEMPROT_DRAM0_SRAM = 0x00000002,
MEMPROT_ALL = 0xFFFFFFFF
} mem_type_prot_t;
typedef enum {
MEMPROT_SPLITLINE_NONE = 0,
MEMPROT_IRAM0_DRAM0_SPLITLINE,
MEMPROT_IRAM0_LINE_0_SPLITLINE,
MEMPROT_IRAM0_LINE_1_SPLITLINE,
MEMPROT_DRAM0_DMA_LINE_0_SPLITLINE,
MEMPROT_DRAM0_DMA_LINE_1_SPLITLINE
} split_line_t;
typedef enum {
MEMPROT_PMS_AREA_NONE = 0,
MEMPROT_IRAM0_PMS_AREA_0,
MEMPROT_IRAM0_PMS_AREA_1,
MEMPROT_IRAM0_PMS_AREA_2,
MEMPROT_IRAM0_PMS_AREA_3,
MEMPROT_DRAM0_PMS_AREA_0,
MEMPROT_DRAM0_PMS_AREA_1,
MEMPROT_DRAM0_PMS_AREA_2,
MEMPROT_DRAM0_PMS_AREA_3
} pms_area_t;
typedef enum
{
MEMPROT_PMS_WORLD_0 = 0,
MEMPROT_PMS_WORLD_1,
MEMPROT_PMS_WORLD_2,
MEMPROT_PMS_WORLD_INVALID = 0xFFFFFFFF
} pms_world_t;
typedef enum
{
MEMPROT_PMS_OP_READ = 0,
MEMPROT_PMS_OP_WRITE,
MEMPROT_PMS_OP_FETCH,
MEMPROT_PMS_OP_INVALID = 0xFFFFFFFF
} pms_operation_type_t;
/**
* @brief Converts Memory protection type to string
*
* @param mem_type Memory protection type (see mem_type_prot_t enum)
*/
const char *esp_memprot_mem_type_to_str(mem_type_prot_t mem_type);
/**
* @brief Converts Split line type to string
*
* @param line_type Split line type (see split_line_t enum)
*/
const char *esp_memprot_split_line_to_str(split_line_t line_type);
/**
* @brief Converts PMS Area type to string
*
* @param area_type PMS Area type (see pms_area_t enum)
*/
const char *esp_memprot_pms_to_str(pms_area_t area_type);
/**
* @brief Returns PMS splitting address for given Split line type
*
* The value is taken from PMS configuration registers (IRam0 range)
* For details on split lines see 'esp_memprot_set_prot_int' function description
*
* @param line_type Split line type (see split_line_t enum)
*
* @return appropriate split line address
*/
uint32_t *esp_memprot_get_split_addr(split_line_t line_type);
/**
* @brief Returns default main IRAM/DRAM splitting address
*
* The address value is given by _iram_text_end global (IRam0 range)
* @return Main I/D split line (IRam0_DRam0_Split_Addr)
*/
void *esp_memprot_get_default_main_split_addr(void);
/**
* @brief Sets a lock for the main IRAM/DRAM splitting address
*
* Locks can be unlocked only by digital system reset
*/
void esp_memprot_set_split_line_lock(void);
/**
* @brief Gets a lock status for the main IRAM/DRAM splitting address
*
* @return true/false (locked/unlocked)
*/
bool esp_memprot_get_split_line_lock(void);
/**
* @brief Sets required split line address
*
* @param line_type Split line type (see split_line_t enum)
* @param line_addr target address from a memory range relevant to given line_type (IRAM/DRAM)
*/
void esp_memprot_set_split_line(split_line_t line_type, const void *line_addr);
/**
* @brief Sets a lock for PMS Area settings of required Memory type
*
* Locks can be unlocked only by digital system reset
*
* @param mem_type Memory protection type (see mem_type_prot_t enum)
*/
void esp_memprot_set_pms_lock(mem_type_prot_t mem_type);
/**
* @brief Gets a lock status for PMS Area settings of required Memory type
*
* @param mem_type Memory protection type (see mem_type_prot_t enum)
*
* @return true/false (locked/unlocked)
*/
bool esp_memprot_get_pms_lock(mem_type_prot_t mem_type);
/**
* @brief Sets permissions for given PMS Area in IRam0 memory range (MEMPROT_IRAM0_SRAM)
*
* @param area_type IRam0 PMS Area type (see pms_area_t enum)
* @param r Read permission flag
* @param w Write permission flag
* @param x Execute permission flag
*/
void esp_memprot_iram_set_pms_area(pms_area_t area_type, bool r, bool w, bool x);
/**
* @brief Gets current permissions for given PMS Area in IRam0 memory range (MEMPROT_IRAM0_SRAM)
*
* @param area_type IRam0 PMS Area type (see pms_area_t enum)
* @param r Read permission flag holder
* @param w Write permission flag holder
* @param x Execute permission flag holder
*/
void esp_memprot_iram_get_pms_area(pms_area_t area_type, bool *r, bool *w, bool *x);
/**
* @brief Sets permissions for given PMS Area in DRam0 memory range (MEMPROT_DRAM0_SRAM)
*
* @param area_type DRam0 PMS Area type (see pms_area_t enum)
* @param r Read permission flag
* @param w Write permission flag
*/
void esp_memprot_dram_set_pms_area(pms_area_t area_type, bool r, bool w);
/**
* @brief Gets current permissions for given PMS Area in DRam0 memory range (MEMPROT_DRAM0_SRAM)
*
* @param area_type DRam0 PMS Area type (see pms_area_t enum)
* @param r Read permission flag holder
* @param w Write permission flag holder
*/
void esp_memprot_dram_get_pms_area(pms_area_t area_type, bool *r, bool *w);
/**
* @brief Sets a lock for PMS interrupt monitor settings of required Memory type
*
* Locks can be unlocked only by digital system reset
*
* @param mem_type Memory protection type (see mem_type_prot_t enum)
*/
void esp_memprot_set_monitor_lock(mem_type_prot_t mem_type);
/**
* @brief Gets a lock status for PMS interrupt monitor settings of required Memory type
*
* @param mem_type Memory protection type (see mem_type_prot_t enum)
*
* @return true/false (locked/unlocked)
*/
bool esp_memprot_get_monitor_lock(mem_type_prot_t mem_type);
/**
* @brief Enable PMS violation interrupt monitoring of required Memory type
*
* @param mem_type Memory protection type (see mem_type_prot_t enum)
* @param enable/disable
*/
void esp_memprot_set_monitor_en(mem_type_prot_t mem_type, bool enable);
/**
* @brief Gets enable/disable status for PMS interrupt monitor settings of required Memory type
*
* @param mem_type Memory protection type (see mem_type_prot_t enum)
*
* @return true/false (enabled/disabled)
*/
bool esp_memprot_get_monitor_en(mem_type_prot_t mem_type);
/**
* @brief Gets CPU ID for currently active PMS violation interrupt
*
* @return CPU ID (CPU_PRO for ESP32C3)
*/
int IRAM_ATTR esp_memprot_intr_get_cpuid(void);
/**
* @brief Clears current interrupt ON flag for given Memory type
*
* Interrupt clearing happens in two steps:
* 1. Interrupt CLR flag is set (to clear the interrupt ON status)
* 2. Interrupt CLR flag is reset (to allow further monitoring)
* This operation is non-atomic by PMS module design
*
* @param mem_type Memory protection type (see mem_type_prot_t enum)
*/
void IRAM_ATTR esp_memprot_monitor_clear_intr(mem_type_prot_t mem_type);
/**
* @brief Returns active PMS violation interrupt (if any)
*
* This function iterates through supported Memory type status registers
* and returns the first interrupt-on flag. If none is found active,
* MEMPROT_NONE is returned.
* Order of checking (in current version):
* 1. MEMPROT_IRAM0_SRAM
* 2. MEMPROT_DRAM0_SRAM
*
* @return mem_type Memory protection type related to active interrupt found (see mem_type_prot_t enum)
*/
mem_type_prot_t IRAM_ATTR esp_memprot_get_active_intr_memtype(void);
/**
* @brief Checks whether any violation interrupt is active
*
* @return true/false (yes/no)
*/
bool IRAM_ATTR esp_memprot_is_locked_any(void);
/**
* @brief Checks whether any violation interrupt is enabled
*
* @return true/false (yes/no)
*/
bool IRAM_ATTR esp_memprot_is_intr_ena_any(void);
/**
* @brief Checks whether any violation interrupt is enabled
*
* @return true/false (yes/no)
*/
bool IRAM_ATTR esp_memprot_get_violate_intr_on(mem_type_prot_t mem_type);
/**
* @brief Returns the address which caused the violation interrupt (if any)
*
* The address is taken from appropriate PMS violation status register, based given Memory type
*
* @param mem_type Memory protection type (see mem_type_prot_t enum)
*
* @return faulting address
*/
uint32_t IRAM_ATTR esp_memprot_get_violate_addr(mem_type_prot_t mem_type);
/**
* @brief Returns the World identifier of the code causing the violation interrupt (if any)
*
* The value is taken from appropriate PMS violation status register, based given Memory type
*
* @param mem_type Memory protection type (see mem_type_prot_t enum)
*
* @return World identifier (see pms_world_t enum)
*/
pms_world_t IRAM_ATTR esp_memprot_get_violate_world(mem_type_prot_t mem_type);
/**
* @brief Returns Read or Write operation type which caused the violation interrupt (if any)
*
* The value (bit) is taken from appropriate PMS violation status register, based given Memory type
*
* @param mem_type Memory protection type (see mem_type_prot_t enum)
*
* @return PMS operation type relevant to mem_type parameter (se pms_operation_type_t)
*/
pms_operation_type_t IRAM_ATTR esp_memprot_get_violate_wr(mem_type_prot_t mem_type);
/**
* @brief Returns LoadStore flag of the operation type which caused the violation interrupt (if any)
*
* The value (bit) is taken from appropriate PMS violation status register, based given Memory type
* Effective only on IRam0 access
*
* @param mem_type Memory protection type (see mem_type_prot_t enum)
*
* @return true/false (LoadStore bit on/off)
*/
bool IRAM_ATTR esp_memprot_get_violate_loadstore(mem_type_prot_t mem_type);
/**
* @brief Returns byte-enables for the address which caused the violation interrupt (if any)
*
* The value is taken from appropriate PMS violation status register, based given Memory type
*
* @param mem_type Memory protection type (see mem_type_prot_t enum)
*
* @return byte-enables
*/
uint32_t IRAM_ATTR esp_memprot_get_violate_byte_en(mem_type_prot_t mem_type);
/**
* @brief Returns raw contents of DRam0 status register 1
*
* @return 32-bit register value
*/
uint32_t IRAM_ATTR esp_memprot_get_dram_status_reg_1(void);
/**
* @brief Returns raw contents of DRam0 status register 2
*
* @return 32-bit register value
*/
uint32_t IRAM_ATTR esp_memprot_get_dram_status_reg_2(void);
/**
* @brief Returns raw contents of IRam0 status register
*
* @return 32-bit register value
*/
uint32_t IRAM_ATTR esp_memprot_get_iram_status_reg(void);
/**
* @brief Register PMS violation interrupt in global interrupt matrix for given Memory type
*
* Memory protection components uses specific interrupt number, see ETS_MEMPROT_ERR_INUM
* The registration makes the panic-handler routine being called when the interrupt appears
*
* @param mem_type Memory protection type (see mem_type_prot_t enum)
*/
void esp_memprot_set_intr_matrix(mem_type_prot_t mem_type);
/**
* @brief Convenient routine for setting the PMS defaults
*
* Called on application startup, depending on CONFIG_ESP_SYSTEM_MEMPROT_FEATURE Kconfig settings
* For implementation details see 'esp_memprot_set_prot_int' description
*
* @param invoke_panic_handler register all interrupts for panic handling (true/false)
* @param lock_feature lock the defaults to prevent further PMS settings changes (true/false)
* @param mem_type_mask 32-bit field of specific PMS parts to configure (see 'esp_memprot_set_prot_int')
*/
void esp_memprot_set_prot(bool invoke_panic_handler, bool lock_feature, uint32_t *mem_type_mask);
/**
* @brief Internal routine for setting the PMS defaults
*
* Called on application startup from within 'esp_memprot_set_prot'. Allows setting a specific splitting address
* (main I/D split line) - see the parameter 'split_addr'. If the 'split_addr' equals to NULL, default I/D split line
* is used (&_iram_text_end) and all the remaining lines share the same address.
* The function sets all the split lines and PMS areas to the same space,
* ie there is a single instruction space and single data space at the end.
* The PMS split lines and permission areas scheme described below:
*
* DRam0/DMA IRam0
* -----------------------------------------------
* ... | IRam0_PMS_0 |
* DRam0_PMS_0 ----------------------------------------------- IRam0_line1_Split_addr
* ... | IRam0_PMS_1 |
* ... ----------------------------------------------- IRam0_line0_Split_addr
* | IRam0_PMS_2 |
* =============================================== IRam0_DRam0_Split_addr (main I/D)
* | DRam0_PMS_1 |
* DRam0_DMA_line0_Split_addr ----------------------------------------------- ...
* | DRam0_PMS_2 | ...
* DRam0_DMA_line1_Split_addr ----------------------------------------------- IRam0_PMS_3
* | DRam0_PMS_3 | ...
* -----------------------------------------------
*
* Default settings provided by 'esp_memprot_set_prot_int' are as follows:
*
* DRam0/DMA IRam0
* -----------------------------------------------
* | IRam0_PMS_0 = IRam0_PMS_1 = IRam0_PMS_2 |
* | DRam0_PMS_0 | IRam0_line1_Split_addr
* DRam0_DMA_line0_Split_addr | | =
* = =============================================== IRam0_line0_Split_addr
* DRam0_DMA_line1_Split_addr | | =
* | DRam0_PMS_1 = DRam0_PMS_2 = DRam0_PMS_3 | IRam0_DRam0_Split_addr (main I/D)
* | IRam0_PMS_3 |
* -----------------------------------------------
*
* Once the memprot feature is locked, it can be unlocked only by digital system reset
*
* @param invoke_panic_handler register all the violation interrupts for panic handling (true/false)
* @param lock_feature lock the defaults to prevent further PMS settings changes (true/false)
* @param split_addr specific main I/D adrees or NULL to use default ($_iram_text_end)
* @param mem_type_mask 32-bit field of specific PMS parts to configure (members of mem_type_prot_t)
*/
void esp_memprot_set_prot_int(bool invoke_panic_handler, bool lock_feature, void *split_addr, uint32_t *mem_type_mask);
/**
* @brief Returns raw contents of PMS interrupt monitor register for given Memory type
*
* @param mem_type Memory protection type (see mem_type_prot_t enum)
*
* @return 32-bit register value
*/
uint32_t esp_memprot_get_monitor_enable_reg(mem_type_prot_t mem_type);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,40 @@
// Copyright 2015-2020 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#pragma once
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @file esp32c3/rtc.h
*
* This file contains declarations of rtc related functions.
*/
/**
* @brief Get current value of RTC counter in microseconds
*
* Note: this function may take up to 1 RTC_SLOW_CLK cycle to execute
*
* @return current value of RTC counter in microseconds
*/
uint64_t esp_rtc_get_time_us(void);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,76 @@
// Copyright 2015-2020 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Acquire lock for HMAC cryptography peripheral
*
* Internally also locks the SHA peripheral, as the HMAC depends on the SHA peripheral
*/
void esp_crypto_hmac_lock_acquire(void);
/**
* @brief Release lock for HMAC cryptography peripheral
*
* Internally also releases the SHA peripheral, as the HMAC depends on the SHA peripheral
*/
void esp_crypto_hmac_lock_release(void);
/**
* @brief Acquire lock for DS cryptography peripheral
*
* Internally also locks the HMAC (which locks SHA), AES and MPI peripheral, as the DS depends on these peripherals
*/
void esp_crypto_ds_lock_acquire(void);
/**
* @brief Release lock for DS cryptography peripheral
*
* Internally also releases the HMAC (which locks SHA), AES and MPI peripheral, as the DS depends on these peripherals
*/
void esp_crypto_ds_lock_release(void);
/**
* @brief Acquire lock for the SHA and AES cryptography peripheral.
*
*/
void esp_crypto_sha_aes_lock_acquire(void);
/**
* @brief Release lock for the SHA and AES cryptography peripheral.
*
*/
void esp_crypto_sha_aes_lock_release(void);
/**
* @brief Acquire lock for the mpi cryptography peripheral.
*
*/
void esp_crypto_mpi_lock_acquire(void);
/**
* @brief Release lock for the mpi/rsa cryptography peripheral.
*
*/
void esp_crypto_mpi_lock_release(void);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,218 @@
// 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 "esp_hmac.h"
#include "esp_err.h"
#ifdef __cplusplus
extern "C" {
#endif
#define ESP32C3_ERR_HW_CRYPTO_DS_HMAC_FAIL ESP_ERR_HW_CRYPTO_BASE + 0x1 /*!< HMAC peripheral problem */
#define ESP32C3_ERR_HW_CRYPTO_DS_INVALID_KEY ESP_ERR_HW_CRYPTO_BASE + 0x2 /*!< given HMAC key isn't correct,
HMAC peripheral problem */
#define ESP32C3_ERR_HW_CRYPTO_DS_INVALID_DIGEST ESP_ERR_HW_CRYPTO_BASE + 0x4 /*!< message digest check failed,
result is invalid */
#define ESP32C3_ERR_HW_CRYPTO_DS_INVALID_PADDING ESP_ERR_HW_CRYPTO_BASE + 0x5 /*!< padding check failed, but result
is produced anyway and can be read*/
#define ESP_DS_IV_BIT_LEN 128
#define ESP_DS_IV_LEN (ESP_DS_IV_BIT_LEN / 8)
#define ESP_DS_SIGNATURE_MAX_BIT_LEN 3072
#define ESP_DS_SIGNATURE_MD_BIT_LEN 256
#define ESP_DS_SIGNATURE_M_PRIME_BIT_LEN 32
#define ESP_DS_SIGNATURE_L_BIT_LEN 32
#define ESP_DS_SIGNATURE_PADDING_BIT_LEN 64
/* Length of parameter 'C' stored in flash, in bytes
- Operands Y, M and r_bar; each 3072 bits
- Operand MD (message digest); 256 bits
- Operands M' and L; each 32 bits
- Operand beta (padding value; 64 bits
*/
#define ESP_DS_C_LEN (((ESP_DS_SIGNATURE_MAX_BIT_LEN * 3 \
+ ESP_DS_SIGNATURE_MD_BIT_LEN \
+ ESP_DS_SIGNATURE_M_PRIME_BIT_LEN \
+ ESP_DS_SIGNATURE_L_BIT_LEN \
+ ESP_DS_SIGNATURE_PADDING_BIT_LEN) / 8))
typedef struct esp_ds_context esp_ds_context_t;
typedef enum {
ESP_DS_RSA_1024 = (1024 / 32) - 1,
ESP_DS_RSA_2048 = (2048 / 32) - 1,
ESP_DS_RSA_3072 = (3072 / 32) - 1
} esp_digital_signature_length_t;
/**
* Encrypted private key data. Recommended to store in flash in this format.
*
* @note This struct has to match to one from the ROM code! This documentation is mostly taken from there.
*/
typedef struct esp_digital_signature_data {
/**
* RSA LENGTH register parameters
* (number of words in RSA key & operands, minus one).
*
* Max value 127 (for RSA 3072).
*
* This value must match the length field encrypted and stored in 'c',
* or invalid results will be returned. (The DS peripheral will
* always use the value in 'c', not this value, so an attacker can't
* alter the DS peripheral results this way, it will just truncate or
* extend the message and the resulting signature in software.)
*
* @note In IDF, the enum type length is the same as of type unsigned, so they can be used interchangably.
* See the ROM code for the original declaration of struct \c ets_ds_data_t.
*/
esp_digital_signature_length_t rsa_length;
/**
* IV value used to encrypt 'c'
*/
uint32_t iv[ESP_DS_IV_BIT_LEN / 32];
/**
* Encrypted Digital Signature parameters. Result of AES-CBC encryption
* of plaintext values. Includes an encrypted message digest.
*/
uint8_t c[ESP_DS_C_LEN];
} esp_ds_data_t;
/**
* Plaintext parameters used by Digital Signature.
*
* This is only used for encrypting the RSA parameters by calling esp_ds_encrypt_params().
* Afterwards, the result can be stored in flash or in other persistent memory.
* The encryption is a prerequisite step before any signature operation can be done.
*/
typedef struct {
uint32_t Y[ESP_DS_SIGNATURE_MAX_BIT_LEN / 32]; //!< RSA exponent
uint32_t M[ESP_DS_SIGNATURE_MAX_BIT_LEN / 32]; //!< RSA modulus
uint32_t Rb[ESP_DS_SIGNATURE_MAX_BIT_LEN / 32]; //!< RSA r inverse operand
uint32_t M_prime; //!< RSA M prime operand
uint32_t length; //!< RSA length in words (32 bit)
} esp_ds_p_data_t;
/**
* @brief Sign the message with a hardware key from specific key slot.
*
* This function is a wrapper around \c esp_ds_finish_sign() and \c esp_ds_start_sign(), so do not use them
* in parallel.
* It blocks until the signing is finished and then returns the signature.
*
* @note This function locks the HMAC, SHA, AES and RSA components during its entire execution time.
*
* @param message the message to be signed; its length is determined by data->rsa_length
* @param data the encrypted signing key data (AES encrypted RSA key + IV)
* @param key_id the HMAC key ID determining the HMAC key of the HMAC which will be used to decrypt the
* signing key data
* @param signature the destination of the signature, should be (data->rsa_length + 1)*4 bytes long
*
* @return
* - ESP_OK if successful, the signature was written to the parameter \c signature.
* - ESP_ERR_INVALID_ARG if one of the parameters is NULL or data->rsa_length is too long or 0
* - ESP_ERR_HW_CRYPTO_DS_HMAC_FAIL if there was an HMAC failure during retrieval of the decryption key
* - ESP_ERR_NO_MEM if there hasn't been enough memory to allocate the context object
* - ESP_ERR_HW_CRYPTO_DS_INVALID_KEY if there's a problem with passing the HMAC key to the DS component
* - ESP_ERR_HW_CRYPTO_DS_INVALID_DIGEST if the message digest didn't match; the signature is invalid.
* - ESP_ERR_HW_CRYPTO_DS_INVALID_PADDING if the message padding is incorrect, the signature can be read though
* since the message digest matches.
*/
esp_err_t esp_ds_sign(const void *message,
const esp_ds_data_t *data,
hmac_key_id_t key_id,
void *signature);
/**
* @brief Start the signing process.
*
* This function yields a context object which needs to be passed to \c esp_ds_finish_sign() to finish the signing
* process.
*
* @note This function locks the HMAC, SHA, AES and RSA components, so the user has to ensure to call
* \c esp_ds_finish_sign() in a timely manner.
*
* @param message the message to be signed; its length is determined by data->rsa_length
* @param data the encrypted signing key data (AES encrypted RSA key + IV)
* @param key_id the HMAC key ID determining the HMAC key of the HMAC which will be used to decrypt the
* signing key data
* @param esp_ds_ctx the context object which is needed for finishing the signing process later
*
* @return
* - ESP_OK if successful, the ds operation was started now and has to be finished with \c esp_ds_finish_sign()
* - ESP_ERR_INVALID_ARG if one of the parameters is NULL or data->rsa_length is too long or 0
* - ESP_ERR_HW_CRYPTO_DS_HMAC_FAIL if there was an HMAC failure during retrieval of the decryption key
* - ESP_ERR_NO_MEM if there hasn't been enough memory to allocate the context object
* - ESP_ERR_HW_CRYPTO_DS_INVALID_KEY if there's a problem with passing the HMAC key to the DS component
*/
esp_err_t esp_ds_start_sign(const void *message,
const esp_ds_data_t *data,
hmac_key_id_t key_id,
esp_ds_context_t **esp_ds_ctx);
/**
* Return true if the DS peripheral is busy, otherwise false.
*
* @note Only valid if \c esp_ds_start_sign() was called before.
*/
bool esp_ds_is_busy(void);
/**
* @brief Finish the signing process.
*
* @param signature the destination of the signature, should be (data->rsa_length + 1)*4 bytes long
* @param esp_ds_ctx the context object retreived by \c esp_ds_start_sign()
*
* @return
* - ESP_OK if successful, the ds operation has been finished and the result is written to signature.
* - ESP_ERR_INVALID_ARG if one of the parameters is NULL
* - ESP_ERR_HW_CRYPTO_DS_INVALID_DIGEST if the message digest didn't match; the signature is invalid.
* This means that the encrypted RSA key parameters are invalid, indicating that they may have been tampered
* with or indicating a flash error, etc.
* - ESP_ERR_HW_CRYPTO_DS_INVALID_PADDING if the message padding is incorrect, the signature can be read though
* since the message digest matches (see TRM for more details).
*/
esp_err_t esp_ds_finish_sign(void *signature, esp_ds_context_t *esp_ds_ctx);
/**
* @brief Encrypt the private key parameters.
*
* The encryption is a prerequisite step before any signature operation can be done.
* It is not strictly necessary to use this encryption function, the encryption could also happen on an external
* device.
*
* @param data Output buffer to store encrypted data, suitable for later use generating signatures.
* The allocated memory must be in internal memory and word aligned since it's filled by DMA. Both is asserted
* at run time.
* @param iv Pointer to 16 byte IV buffer, will be copied into 'data'. Should be randomly generated bytes each time.
* @param p_data Pointer to input plaintext key data. The expectation is this data will be deleted after this process
* is done and 'data' is stored.
* @param key Pointer to 32 bytes of key data. Type determined by key_type parameter. The expectation is the
* corresponding HMAC key will be stored to efuse and then permanently erased.
*
* @return
* - ESP_OK if successful, the ds operation has been finished and the result is written to signature.
* - ESP_ERR_INVALID_ARG if one of the parameters is NULL or p_data->rsa_length is too long
*/
esp_err_t esp_ds_encrypt_params(esp_ds_data_t *data,
const void *iv,
const esp_ds_p_data_t *p_data,
const void *key);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,67 @@
// Copyright 2015-2020 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef _ESP_HMAC_H_
#define _ESP_HMAC_H_
#include <stdbool.h>
#include "esp_err.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* The possible efuse keys for the HMAC peripheral
*/
typedef enum {
HMAC_KEY0 = 0,
HMAC_KEY1,
HMAC_KEY2,
HMAC_KEY3,
HMAC_KEY4,
HMAC_KEY5,
HMAC_KEY_MAX
} hmac_key_id_t;
/**
* @brief
* Calculate the HMAC of a given message.
*
* Calculate the HMAC \c hmac of a given message \c message with length \c message_len.
* SHA256 is used for the calculation (fixed on ESP32S2).
*
* @note Uses the HMAC peripheral in "upstream" mode.
*
* @param key_id Determines which of the 6 key blocks in the efuses should be used for the HMAC calcuation.
* The corresponding purpose field of the key block in the efuse must be set to the HMAC upstream purpose value.
* @param message the message for which to calculate the HMAC
* @param message_len message length
* return ESP_ERR_INVALID_STATE if unsuccessful
* @param [out] hmac the hmac result; the buffer behind the provided pointer must be 32 bytes long
*
* @return
* * ESP_OK, if the calculation was successful,
* * ESP_FAIL, if the hmac calculation failed
*/
esp_err_t esp_hmac_calculate(hmac_key_id_t key_id,
const void *message,
size_t message_len,
uint8_t *hmac);
#ifdef __cplusplus
}
#endif
#endif // _ESP_HMAC_H_

View File

@ -0,0 +1,118 @@
/**
* ESP32-C3 Linker Script Memory Layout
* This file describes the memory layout (memory blocks) by virtual memory addresses.
* This linker script is passed through the C preprocessor to include configuration options.
* Please use preprocessor features sparingly!
* Restrict to simple macros with numeric values, and/or #if/#endif blocks.
*/
#include "sdkconfig.h"
#ifdef CONFIG_BOOTLOADER_CUSTOM_RESERVE_RTC
#define ESP_BOOTLOADER_RESERVE_RTC (CONFIG_BOOTLOADER_RESERVE_RTC_SIZE + CONFIG_BOOTLOADER_CUSTOM_RESERVE_RTC_SIZE)
#elif defined(CONFIG_BOOTLOADER_SKIP_VALIDATE_IN_DEEP_SLEEP)
#define ESP_BOOTLOADER_RESERVE_RTC (CONFIG_BOOTLOADER_RESERVE_RTC_SIZE)
#else
#define ESP_BOOTLOADER_RESERVE_RTC 0
#endif
#define SRAM_IRAM_START 0x4037C000
#define SRAM_DRAM_START 0x3FC7C000
#define ICACHE_SIZE 0x4000 /* ICache size is fixed to 16KB on ESP32-C3 */
#define I_D_SRAM_OFFSET (SRAM_IRAM_START - SRAM_DRAM_START)
#define SRAM_DRAM_END 0x403D0000 - I_D_SRAM_OFFSET /* 2nd stage bootloader iram_loader_seg start address */
#define SRAM_IRAM_ORG (SRAM_IRAM_START + ICACHE_SIZE)
#define SRAM_DRAM_ORG (SRAM_DRAM_START + ICACHE_SIZE)
#define I_D_SRAM_SIZE SRAM_DRAM_END - SRAM_DRAM_ORG
#if CONFIG_ESP32C3_USE_FIXED_STATIC_RAM_SIZE
ASSERT((CONFIG_ESP32C3_FIXED_STATIC_RAM_SIZE <= I_D_SRAM_SIZE), "Fixed static ram data does not fit.")
#define DRAM0_0_SEG_LEN CONFIG_ESP3C3_FIXED_STATIC_RAM_SIZE
#else
#define DRAM0_0_SEG_LEN I_D_SRAM_SIZE
#endif // CONFIG_ESP32C3_USE_FIXED_STATIC_RAM_SIZE
MEMORY
{
/**
* All these values assume the flash cache is on, and have the blocks this uses subtracted from the length
* of the various regions. The 'data access port' dram/drom regions map to the same iram/irom regions but
* are connected to the data port of the CPU and eg allow byte-wise access.
*/
/* IRAM for PRO CPU. */
iram0_0_seg (RX) : org = SRAM_IRAM_ORG, len = I_D_SRAM_SIZE
#if CONFIG_APP_BUILD_USE_FLASH_SECTIONS
/* Flash mapped instruction data */
iram0_2_seg (RX) : org = 0x42000020, len = 0x8000000-0x20
/**
* (0x20 offset above is a convenience for the app binary image generation.
* Flash cache has 64KB pages. The .bin file which is flashed to the chip
* has a 0x18 byte file header, and each segment has a 0x08 byte segment
* header. Setting this offset makes it simple to meet the flash cache MMU's
* constraint that (paddr % 64KB == vaddr % 64KB).)
*/
#endif // CONFIG_APP_BUILD_USE_FLASH_SECTIONS
/**
* Shared data RAM, excluding memory reserved for ROM bss/data/stack.
* Enabling Bluetooth & Trace Memory features in menuconfig will decrease the amount of RAM available.
*/
dram0_0_seg (RW) : org = SRAM_DRAM_ORG, len = DRAM0_0_SEG_LEN
#if CONFIG_APP_BUILD_USE_FLASH_SECTIONS
/* Flash mapped constant data */
drom0_0_seg (R) : org = 0x3C000020, len = 0x8000000-0x20
/* (See iram0_2_seg for meaning of 0x20 offset in the above.) */
#endif // CONFIG_APP_BUILD_USE_FLASH_SECTIONS
/**
* RTC fast memory (executable). Persists over deep sleep.
*/
rtc_iram_seg(RWX) : org = 0x50000000, len = 0x2000 - ESP_BOOTLOADER_RESERVE_RTC
}
#if CONFIG_ESP32C3_USE_FIXED_STATIC_RAM_SIZE
/* static data ends at defined address */
_static_data_end = 0x3FCA0000 + DRAM0_0_SEG_LEN;
#else
_static_data_end = _bss_end;
#endif // CONFIG_ESP32C3_USE_FIXED_STATIC_RAM_SIZE
/* Heap ends at top of dram0_0_seg */
_heap_end = 0x40000000;
_data_seg_org = ORIGIN(rtc_data_seg);
/**
* The lines below define location alias for .rtc.data section
* As C3 only has RTC fast memory, this is not configurable like on other targets
*/
REGION_ALIAS("rtc_data_seg", rtc_iram_seg );
REGION_ALIAS("rtc_slow_seg", rtc_iram_seg );
REGION_ALIAS("rtc_data_location", rtc_iram_seg );
#if CONFIG_APP_BUILD_USE_FLASH_SECTIONS
REGION_ALIAS("default_code_seg", iram0_2_seg);
#else
REGION_ALIAS("default_code_seg", iram0_0_seg);
#endif // CONFIG_APP_BUILD_USE_FLASH_SECTIONS
#if CONFIG_APP_BUILD_USE_FLASH_SECTIONS
REGION_ALIAS("default_rodata_seg", drom0_0_seg);
#else
REGION_ALIAS("default_rodata_seg", dram0_0_seg);
#endif // CONFIG_APP_BUILD_USE_FLASH_SECTIONS
/**
* If rodata default segment is placed in `drom0_0_seg`, then flash's first rodata section must
* also be first in the segment.
*/
#if CONFIG_APP_BUILD_USE_FLASH_SECTIONS
ASSERT(_flash_rodata_dummy_start == ORIGIN(default_rodata_seg),
".flash_rodata_dummy section must be placed at the beginning of the rodata segment.")
#endif

View File

@ -0,0 +1,30 @@
PROVIDE ( UART0 = 0x60000000 );
PROVIDE ( UART1 = 0x60010000 );
PROVIDE ( SPIMEM1 = 0x60002000 );
PROVIDE ( SPIMEM0 = 0x60003000 );
PROVIDE ( GPIO = 0x60004000 );
PROVIDE ( SIGMADELTA = 0x60004f00 );
PROVIDE ( RTCCNTL = 0x60008000 );
PROVIDE ( RTCIO = 0x60008400 );
PROVIDE ( HINF = 0x6000B000 );
PROVIDE ( I2S1 = 0x6002d000 );
PROVIDE ( I2C0 = 0x60013000 );
PROVIDE ( UHCI0 = 0x60014000 );
PROVIDE ( UHCI1 = 0x6000c000 );
PROVIDE ( HOST = 0x60015000 );
PROVIDE ( RMT = 0x60016000 );
PROVIDE ( RMTMEM = 0x60016400 );
PROVIDE ( PCNT = 0x60017000 );
PROVIDE ( SLC = 0x60018000 );
PROVIDE ( LEDC = 0x60019000 );
PROVIDE ( TIMERG0 = 0x6001F000 );
PROVIDE ( TIMERG1 = 0x60020000 );
PROVIDE ( SYSTIMER = 0x60023000 );
PROVIDE ( GPSPI2 = 0x60024000 );
PROVIDE ( GPSPI3 = 0x60025000 );
PROVIDE ( SYSCON = 0x60026000 );
PROVIDE ( TWAI = 0x6002B000 );
PROVIDE ( GPSPI4 = 0x60037000 );
PROVIDE ( APB_SARADC = 0x60040000 );
PROVIDE ( USB_SERIAL_JTAG = 0x60043000 );
PROVIDE ( GDMA = 0x6003F000 );

View File

@ -0,0 +1,392 @@
/* Default entry point */
ENTRY(call_start_cpu0);
SECTIONS
{
/**
* RTC fast memory holds RTC wake stub code,
* including from any source file named rtc_wake_stub*.c
*/
.rtc.text :
{
. = ALIGN(4);
mapping[rtc_text]
*rtc_wake_stub*.*(.literal .text .literal.* .text.*)
_rtc_text_end = ABSOLUTE(.);
} > rtc_iram_seg
/**
* This section is required to skip rtc.text area because rtc_iram_seg and
* rtc_data_seg are reflect the same address space on different buses.
*/
.rtc.dummy :
{
_rtc_dummy_start = ABSOLUTE(.);
_rtc_fast_start = ABSOLUTE(.);
. = SIZEOF(.rtc.text);
_rtc_dummy_end = ABSOLUTE(.);
} > rtc_data_seg
/**
* This section located in RTC FAST Memory area.
* It holds data marked with RTC_FAST_ATTR attribute.
* See the file "esp_attr.h" for more information.
*/
.rtc.force_fast :
{
. = ALIGN(4);
_rtc_force_fast_start = ABSOLUTE(.);
mapping[rtc_force_fast]
*(.rtc.force_fast .rtc.force_fast.*)
. = ALIGN(4) ;
_rtc_force_fast_end = ABSOLUTE(.);
} > rtc_data_seg
/**
* RTC data section holds RTC wake stub
* data/rodata, including from any source file
* named rtc_wake_stub*.c and the data marked with
* RTC_DATA_ATTR, RTC_RODATA_ATTR attributes.
* The memory location of the data is dependent on
* CONFIG_ESP32C3_RTCDATA_IN_FAST_MEM option.
*/
.rtc.data :
{
_rtc_data_start = ABSOLUTE(.);
mapping[rtc_data]
*rtc_wake_stub*.*(.data .rodata .data.* .rodata.* .bss .bss.*)
_rtc_data_end = ABSOLUTE(.);
} > rtc_data_location
/* RTC bss, from any source file named rtc_wake_stub*.c */
.rtc.bss (NOLOAD) :
{
_rtc_bss_start = ABSOLUTE(.);
*rtc_wake_stub*.*(.bss .bss.*)
*rtc_wake_stub*.*(COMMON)
mapping[rtc_bss]
_rtc_bss_end = ABSOLUTE(.);
} > rtc_data_location
/**
* This section holds data that should not be initialized at power up
* and will be retained during deep sleep.
* User data marked with RTC_NOINIT_ATTR will be placed
* into this section. See the file "esp_attr.h" for more information.
* The memory location of the data is dependent on CONFIG_ESP32C3_RTCDATA_IN_FAST_MEM option.
*/
.rtc_noinit (NOLOAD):
{
. = ALIGN(4);
_rtc_noinit_start = ABSOLUTE(.);
*(.rtc_noinit .rtc_noinit.*)
. = ALIGN(4) ;
_rtc_noinit_end = ABSOLUTE(.);
} > rtc_data_location
/**
* This section located in RTC SLOW Memory area.
* It holds data marked with RTC_SLOW_ATTR attribute.
* See the file "esp_attr.h" for more information.
*/
.rtc.force_slow :
{
. = ALIGN(4);
_rtc_force_slow_start = ABSOLUTE(.);
*(.rtc.force_slow .rtc.force_slow.*)
. = ALIGN(4) ;
_rtc_force_slow_end = ABSOLUTE(.);
} > rtc_slow_seg
/* Get size of rtc slow data based on rtc_data_location alias */
_rtc_slow_length = (ORIGIN(rtc_slow_seg) == ORIGIN(rtc_data_location))
? (_rtc_force_slow_end - _rtc_data_start)
: (_rtc_force_slow_end - _rtc_force_slow_start);
_rtc_fast_length = (ORIGIN(rtc_slow_seg) == ORIGIN(rtc_data_location))
? (_rtc_force_fast_end - _rtc_fast_start)
: (_rtc_noinit_end - _rtc_fast_start);
ASSERT((_rtc_slow_length <= LENGTH(rtc_slow_seg)),
"RTC_SLOW segment data does not fit.")
ASSERT((_rtc_fast_length <= LENGTH(rtc_data_seg)),
"RTC_FAST segment data does not fit.")
.iram0.text :
{
_iram_start = ABSOLUTE(.);
/* Vectors go to start of IRAM */
ASSERT(ABSOLUTE(.) % 0x100 == 0, "vector address must be 256 byte aligned");
KEEP(*(.exception_vectors.text));
. = ALIGN(4);
_invalid_pc_placeholder = ABSOLUTE(.);
/* Code marked as running out of IRAM */
_iram_text_start = ABSOLUTE(.);
mapping[iram0_text]
} > iram0_0_seg
/**
* This section is required to skip .iram0.text area because iram0_0_seg and
* dram0_0_seg reflect the same address space on different buses.
*/
.dram0.dummy (NOLOAD):
{
. = ORIGIN(dram0_0_seg) + _iram_end - _iram_start;
} > dram0_0_seg
.dram0.data :
{
_data_start = ABSOLUTE(.);
*(.gnu.linkonce.d.*)
*(.data1)
__global_pointer$ = . + 0x800;
*(.sdata)
*(.sdata.*)
*(.gnu.linkonce.s.*)
*(.sdata2)
*(.sdata2.*)
*(.gnu.linkonce.s2.*)
*(.jcr)
_esp_system_init_fn_array_start = ABSOLUTE(.);
KEEP (*(SORT(.esp_system_init_fn) SORT(.esp_system_init_fn.*)))
_esp_system_init_fn_array_end = ABSOLUTE(.);
mapping[dram0_data]
_data_end = ABSOLUTE(.);
. = ALIGN(4);
} > dram0_0_seg
/**
* This section holds data that should not be initialized at power up.
* The section located in Internal SRAM memory region. The macro _NOINIT
* can be used as attribute to place data into this section.
* See the "esp_attr.h" file for more information.
*/
.noinit (NOLOAD):
{
. = ALIGN(4);
_noinit_start = ABSOLUTE(.);
*(.noinit .noinit.*)
. = ALIGN(4) ;
_noinit_end = ABSOLUTE(.);
} > dram0_0_seg
/* Shared RAM */
.dram0.bss (NOLOAD) :
{
. = ALIGN (8);
_bss_start = ABSOLUTE(.);
mapping[dram0_bss]
*(.dynsbss)
*(.sbss)
*(.sbss.*)
*(.gnu.linkonce.sb.*)
*(.scommon)
*(.sbss2)
*(.sbss2.*)
*(.gnu.linkonce.sb2.*)
*(.dynbss)
*(.share.mem)
*(.gnu.linkonce.b.*)
. = ALIGN (8);
_bss_end = ABSOLUTE(.);
} > dram0_0_seg
ASSERT(((_bss_end - ORIGIN(dram0_0_seg)) <= LENGTH(dram0_0_seg)), "DRAM segment data does not fit.")
.flash.text :
{
_stext = .;
_instruction_reserved_start = ABSOLUTE(.);
_text_start = ABSOLUTE(.);
mapping[flash_text]
*(.stub .gnu.warning .gnu.linkonce.literal.* .gnu.linkonce.t.*.literal .gnu.linkonce.t.*)
*(.irom0.text) /* catch stray ICACHE_RODATA_ATTR */
*(.fini.literal)
*(.fini)
*(.gnu.version)
/** CPU will try to prefetch up to 16 bytes of
* of instructions. This means that any configuration (e.g. MMU, PMS) must allow
* safe access to up to 16 bytes after the last real instruction, add
* dummy bytes to ensure this
*/
. += 16;
_text_end = ABSOLUTE(.);
_instruction_reserved_end = ABSOLUTE(.);
_etext = .;
/**
* Similar to _iram_start, this symbol goes here so it is
* resolved by addr2line in preference to the first symbol in
* the flash.text segment.
*/
_flash_cache_start = ABSOLUTE(0);
} > default_code_seg
/**
* This dummy section represents the .flash.text section but in default_rodata_seg.
* Thus, it must have its alignement and (at least) its size.
*/
.flash_rodata_dummy (NOLOAD):
{
_flash_rodata_dummy_start = .;
/* Start at the same alignement constraint than .flash.text */
. = ALIGN(ALIGNOF(.flash.text));
/* Create an empty gap as big as .flash.text section */
. = . + SIZEOF(.flash.text);
/* Prepare the alignement of the section above. Few bytes (0x20) must be
* added for the mapping header. */
. = ALIGN(0x10000) + 0x20;
_rodata_reserved_start = .;
} > default_rodata_seg
.flash.appdesc : ALIGN(0x10)
{
_rodata_start = ABSOLUTE(.);
*(.rodata_desc .rodata_desc.*) /* Should be the first. App version info. DO NOT PUT ANYTHING BEFORE IT! */
*(.rodata_custom_desc .rodata_custom_desc.*) /* Should be the second. Custom app version info. DO NOT PUT ANYTHING BEFORE IT! */
/* Create an empty gap within this section. Thanks to this, the end of this
* section will match .flash.rodata's begin address. Thus, both sections
* will be merged when creating the final bin image. */
. = ALIGN(ALIGNOF(.flash.rodata));
} >default_rodata_seg
.flash.rodata : ALIGN(0x10)
{
_flash_rodata_start = ABSOLUTE(.);
mapping[flash_rodata]
*(.irom1.text) /* catch stray ICACHE_RODATA_ATTR */
*(.gnu.linkonce.r.*)
*(.rodata1)
__XT_EXCEPTION_TABLE_ = ABSOLUTE(.);
*(.xt_except_table)
*(.gcc_except_table .gcc_except_table.*)
*(.gnu.linkonce.e.*)
*(.gnu.version_r)
. = (. + 3) & ~ 3;
__eh_frame = ABSOLUTE(.);
KEEP(*(.eh_frame))
. = (. + 7) & ~ 3;
/*
* C++ constructor and destructor tables
* Don't include anything from crtbegin.o or crtend.o, as IDF doesn't use toolchain crt.
*
* RISC-V gcc is configured with --enable-initfini-array so it emits an .init_array section instead.
* But the init_priority sections will be sorted for iteration in ascending order during startup.
* The rest of the init_array sections is sorted for iteration in descending order during startup, however.
* Hence a different section is generated for the init_priority functions which is iterated in
* ascending order during startup. The corresponding code can be found in startup.c.
*/
__init_priority_array_start = ABSOLUTE(.);
KEEP (*(EXCLUDE_FILE (*crtend.* *crtbegin.*) .init_array.*))
__init_priority_array_end = ABSOLUTE(.);
__init_array_start = ABSOLUTE(.);
KEEP (*(EXCLUDE_FILE (*crtend.* *crtbegin.*) .init_array))
__init_array_end = ABSOLUTE(.);
KEEP (*crtbegin.*(.dtors))
KEEP (*(EXCLUDE_FILE (*crtend.*) .dtors))
KEEP (*(SORT(.dtors.*)))
KEEP (*(.dtors))
/* C++ exception handlers table: */
__XT_EXCEPTION_DESCS_ = ABSOLUTE(.);
*(.xt_except_desc)
*(.gnu.linkonce.h.*)
__XT_EXCEPTION_DESCS_END__ = ABSOLUTE(.);
*(.xt_except_desc_end)
*(.dynamic)
*(.gnu.version_d)
/* Addresses of memory regions reserved via SOC_RESERVE_MEMORY_REGION() */
soc_reserved_memory_region_start = ABSOLUTE(.);
KEEP (*(.reserved_memory_address))
soc_reserved_memory_region_end = ABSOLUTE(.);
_rodata_end = ABSOLUTE(.);
/* Literals are also RO data. */
_lit4_start = ABSOLUTE(.);
*(*.lit4)
*(.lit4.*)
*(.gnu.linkonce.lit4.*)
_lit4_end = ABSOLUTE(.);
. = ALIGN(4);
_thread_local_start = ABSOLUTE(.);
*(.tdata)
*(.tdata.*)
*(.tbss)
*(.tbss.*)
*(.srodata)
*(.srodata.*)
_thread_local_end = ABSOLUTE(.);
_rodata_reserved_end = ABSOLUTE(.);
. = ALIGN(4);
} > default_rodata_seg
/* Marks the end of IRAM code segment */
.iram0.text_end (NOLOAD) :
{
/* C3 memprot requires 512 B alignment for split lines */
. = ALIGN (0x200);
/* iram_end_test section exists for use by memprot unit tests only */
*(.iram_end_test)
_iram_text_end = ABSOLUTE(.);
} > iram0_0_seg
.iram0.data :
{
. = ALIGN(16);
_iram_data_start = ABSOLUTE(.);
mapping[iram0_data]
_iram_data_end = ABSOLUTE(.);
} > iram0_0_seg
.iram0.bss (NOLOAD) :
{
. = ALIGN(16);
_iram_bss_start = ABSOLUTE(.);
mapping[iram0_bss]
_iram_bss_end = ABSOLUTE(.);
. = ALIGN(16);
_iram_end = ABSOLUTE(.);
} > iram0_0_seg
/* Marks the end of data, bss and possibly rodata */
.dram0.heap_start (NOLOAD) :
{
. = ALIGN (16);
_heap_start = ABSOLUTE(.);
} > dram0_0_seg
}
ASSERT(((_iram_end - ORIGIN(iram0_0_seg)) <= LENGTH(iram0_0_seg)),
"IRAM0 segment data does not fit.")
ASSERT(((_heap_start - ORIGIN(dram0_0_seg)) <= LENGTH(dram0_0_seg)),
"DRAM segment data does not fit.")

View File

@ -0,0 +1,616 @@
// 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.
/* INTERNAL API
* implementation of PMS memory protection features
*/
#include <stdio.h>
#include "sdkconfig.h"
#include "soc/sensitive_reg.h"
#include "soc/dport_access.h"
#include "soc/periph_defs.h"
#include "esp_intr_alloc.h"
#include "hal/memprot_ll.h"
#include "esp32c3/memprot.h"
#include "riscv/interrupt.h"
#include "esp32c3/rom/ets_sys.h"
#include "esp_log.h"
extern int _iram_text_end;
static const char *TAG = "memprot";
const char *esp_memprot_mem_type_to_str(mem_type_prot_t mem_type)
{
switch (mem_type) {
case MEMPROT_NONE:
return "NONE";
case MEMPROT_IRAM0_SRAM:
return "IRAM0_SRAM";
case MEMPROT_DRAM0_SRAM:
return "DRAM0_SRAM";
case MEMPROT_ALL:
return "ALL";
default:
return "UNKNOWN";
}
}
const char *esp_memprot_split_line_to_str(split_line_t line_type)
{
switch (line_type) {
case MEMPROT_IRAM0_DRAM0_SPLITLINE:
return "MEMPROT_IRAM0_DRAM0_SPLITLINE";
case MEMPROT_IRAM0_LINE_0_SPLITLINE:
return "MEMPROT_IRAM0_LINE_0_SPLITLINE";
case MEMPROT_IRAM0_LINE_1_SPLITLINE:
return "MEMPROT_IRAM0_LINE_1_SPLITLINE";
case MEMPROT_DRAM0_DMA_LINE_0_SPLITLINE:
return "MEMPROT_DRAM0_DMA_LINE_0_SPLITLINE";
case MEMPROT_DRAM0_DMA_LINE_1_SPLITLINE:
return "MEMPROT_DRAM0_DMA_LINE_1_SPLITLINE";
default:
return "UNKNOWN";
}
}
const char *esp_memprot_pms_to_str(pms_area_t area_type)
{
switch (area_type) {
case MEMPROT_IRAM0_PMS_AREA_0:
return "MEMPROT_IRAM0_PMS_AREA_0";
case MEMPROT_IRAM0_PMS_AREA_1:
return "MEMPROT_IRAM0_PMS_AREA_1";
case MEMPROT_IRAM0_PMS_AREA_2:
return "MEMPROT_IRAM0_PMS_AREA_2";
case MEMPROT_IRAM0_PMS_AREA_3:
return "MEMPROT_IRAM0_PMS_AREA_3";
case MEMPROT_DRAM0_PMS_AREA_0:
return "MEMPROT_DRAM0_PMS_AREA_0";
case MEMPROT_DRAM0_PMS_AREA_1:
return "MEMPROT_DRAM0_PMS_AREA_1";
case MEMPROT_DRAM0_PMS_AREA_2:
return "MEMPROT_DRAM0_PMS_AREA_2";
case MEMPROT_DRAM0_PMS_AREA_3:
return "MEMPROT_DRAM0_PMS_AREA_3";
default:
return "UNKNOWN";
}
}
/* split lines */
void *esp_memprot_get_default_main_split_addr()
{
return &_iram_text_end;
}
uint32_t *esp_memprot_get_split_addr(split_line_t line_type)
{
switch ( line_type ) {
case MEMPROT_IRAM0_DRAM0_SPLITLINE:
return memprot_ll_get_iram0_split_line_main_I_D();
case MEMPROT_IRAM0_LINE_0_SPLITLINE:
return memprot_ll_get_iram0_split_line_I_0();
case MEMPROT_IRAM0_LINE_1_SPLITLINE:
return memprot_ll_get_iram0_split_line_I_1();
case MEMPROT_DRAM0_DMA_LINE_0_SPLITLINE:
return memprot_ll_get_dram0_split_line_D_0();
case MEMPROT_DRAM0_DMA_LINE_1_SPLITLINE:
return memprot_ll_get_dram0_split_line_D_1();
default:
abort();
}
}
void esp_memprot_set_split_line_lock()
{
memprot_ll_set_iram0_dram0_split_line_lock();
}
bool esp_memprot_get_split_line_lock()
{
return memprot_ll_get_iram0_dram0_split_line_lock();
}
void esp_memprot_set_split_line(split_line_t line_type, const void *line_addr)
{
ESP_EARLY_LOGD(TAG, "Setting split line %s, addr: 0x%08X", esp_memprot_split_line_to_str(line_type), (uint32_t)line_addr);
//split-line must be divisible by 512 (PMS module restriction)
assert( ((uint32_t)line_addr) % 0x200 == 0 );
switch ( line_type ) {
case MEMPROT_IRAM0_DRAM0_SPLITLINE:
memprot_ll_set_iram0_split_line_main_I_D(line_addr);
break;
case MEMPROT_IRAM0_LINE_0_SPLITLINE:
memprot_ll_set_iram0_split_line_I_0(line_addr);
break;
case MEMPROT_IRAM0_LINE_1_SPLITLINE:
memprot_ll_set_iram0_split_line_I_1(line_addr);
break;
case MEMPROT_DRAM0_DMA_LINE_0_SPLITLINE:
memprot_ll_set_dram0_split_line_D_0(line_addr);
break;
case MEMPROT_DRAM0_DMA_LINE_1_SPLITLINE:
memprot_ll_set_dram0_split_line_D_1(line_addr);
break;
default:
ESP_EARLY_LOGE(TAG, "Invalid split line type, aborting: 0x%08X", (uint32_t)line_addr);
abort();
}
}
/* PMS */
void esp_memprot_set_pms_lock(mem_type_prot_t mem_type)
{
ESP_EARLY_LOGD(TAG, "esp_memprot_set_pms_lock(%s)", esp_memprot_mem_type_to_str(mem_type));
switch ( mem_type ) {
case MEMPROT_IRAM0_SRAM:
memprot_ll_iram0_set_pms_lock();
break;
case MEMPROT_DRAM0_SRAM:
memprot_ll_dram0_set_pms_lock();
break;
default:
ESP_EARLY_LOGE(TAG, "Invalid mem_type (%s), aborting", esp_memprot_mem_type_to_str(mem_type));
abort();
}
}
bool esp_memprot_get_pms_lock(mem_type_prot_t mem_type)
{
ESP_EARLY_LOGD(TAG, "esp_memprot_get_pms_lock(%s)", esp_memprot_mem_type_to_str(mem_type));
switch ( mem_type ) {
case MEMPROT_IRAM0_SRAM:
return memprot_ll_iram0_get_pms_lock();
case MEMPROT_DRAM0_SRAM:
return memprot_ll_dram0_get_pms_lock();
default:
ESP_EARLY_LOGE(TAG, "Invalid mem_type (%s), aborting", esp_memprot_mem_type_to_str(mem_type));
abort();
}
}
void esp_memprot_iram_set_pms_area(pms_area_t area_type, bool r, bool w, bool x)
{
ESP_EARLY_LOGD(TAG, "esp_memprot_iram_set_pms_area(area:%s r:%u w:%u, x:%u)", esp_memprot_pms_to_str(area_type), r, w, x);
switch ( area_type ) {
case MEMPROT_IRAM0_PMS_AREA_0:
memprot_ll_iram0_set_pms_area_0(r, w, x);
break;
case MEMPROT_IRAM0_PMS_AREA_1:
memprot_ll_iram0_set_pms_area_1(r, w, x);
break;
case MEMPROT_IRAM0_PMS_AREA_2:
memprot_ll_iram0_set_pms_area_2(r, w, x);
break;
case MEMPROT_IRAM0_PMS_AREA_3:
memprot_ll_iram0_set_pms_area_3(r, w, x);
break;
default:
ESP_EARLY_LOGE(TAG, "Invalid area_type %d", esp_memprot_pms_to_str(area_type));
abort();
}
}
void esp_memprot_iram_get_pms_area(pms_area_t area_type, bool *r, bool *w, bool *x)
{
ESP_EARLY_LOGD(TAG, "esp_memprot_iram_get_pms_area(area:%s r:%u w:%u)", esp_memprot_pms_to_str(area_type), r, w);
switch ( area_type ) {
case MEMPROT_IRAM0_PMS_AREA_0:
memprot_ll_iram0_get_pms_area_0(r, w, x);
break;
case MEMPROT_IRAM0_PMS_AREA_1:
memprot_ll_iram0_get_pms_area_1(r, w, x);
break;
case MEMPROT_IRAM0_PMS_AREA_2:
memprot_ll_iram0_get_pms_area_2(r, w, x);
break;
case MEMPROT_IRAM0_PMS_AREA_3:
memprot_ll_iram0_get_pms_area_3(r, w, x);
break;
default:
ESP_EARLY_LOGE(TAG, "Invalid area_type %d", esp_memprot_pms_to_str(area_type));
abort();
}
}
void esp_memprot_dram_set_pms_area(pms_area_t area_type, bool r, bool w)
{
ESP_EARLY_LOGD(TAG, "esp_memprot_dram_set_pms_area(area:%s r:%u w:%u)", esp_memprot_pms_to_str(area_type), r, w);
switch ( area_type ) {
case MEMPROT_DRAM0_PMS_AREA_0:
memprot_ll_dram0_set_pms_area_0(r, w);
break;
case MEMPROT_DRAM0_PMS_AREA_1:
memprot_ll_dram0_set_pms_area_1(r, w);
break;
case MEMPROT_DRAM0_PMS_AREA_2:
memprot_ll_dram0_set_pms_area_2(r, w);
break;
case MEMPROT_DRAM0_PMS_AREA_3:
memprot_ll_dram0_set_pms_area_3(r, w);
break;
default:
ESP_EARLY_LOGE(TAG, "Invalid area_type %d", esp_memprot_pms_to_str(area_type));
abort();
}
}
void esp_memprot_dram_get_pms_area(pms_area_t area_type, bool *r, bool *w)
{
ESP_EARLY_LOGD(TAG, "esp_memprot_dram_get_pms_area(area:%s r:%u w:%u)", esp_memprot_pms_to_str(area_type), r, w);
switch ( area_type ) {
case MEMPROT_DRAM0_PMS_AREA_0:
memprot_ll_dram0_get_pms_area_0(r, w);
break;
case MEMPROT_DRAM0_PMS_AREA_1:
memprot_ll_dram0_get_pms_area_1(r, w);
break;
case MEMPROT_DRAM0_PMS_AREA_2:
memprot_ll_dram0_get_pms_area_2(r, w);
break;
case MEMPROT_DRAM0_PMS_AREA_3:
memprot_ll_dram0_get_pms_area_3(r, w);
break;
default:
ESP_EARLY_LOGE(TAG, "Invalid area_type %d", esp_memprot_pms_to_str(area_type));
abort();
}
}
/* monitor */
void esp_memprot_set_monitor_lock(mem_type_prot_t mem_type)
{
ESP_EARLY_LOGD(TAG, "esp_memprot_set_monitor_lock(%s)", esp_memprot_mem_type_to_str(mem_type));
switch ( mem_type ) {
case MEMPROT_IRAM0_SRAM:
memprot_ll_iram0_set_monitor_lock();
break;
case MEMPROT_DRAM0_SRAM:
memprot_ll_dram0_set_monitor_lock();
break;
default:
ESP_EARLY_LOGE(TAG, "Invalid mem_type (%s), aborting", esp_memprot_mem_type_to_str(mem_type));
abort();
}
}
bool esp_memprot_get_monitor_lock(mem_type_prot_t mem_type)
{
ESP_EARLY_LOGD(TAG, "esp_memprot_get_monitor_lock(%s)", esp_memprot_mem_type_to_str(mem_type));
switch ( mem_type ) {
case MEMPROT_IRAM0_SRAM:
return memprot_ll_iram0_get_monitor_lock();
case MEMPROT_DRAM0_SRAM:
return memprot_ll_dram0_get_monitor_lock();
default:
ESP_EARLY_LOGE(TAG, "Invalid mem_type (%s), aborting", esp_memprot_mem_type_to_str(mem_type));
abort();
}
}
void esp_memprot_set_monitor_en(mem_type_prot_t mem_type, bool enable)
{
ESP_EARLY_LOGD(TAG, "esp_memprot_set_monitor_en(%s)", esp_memprot_mem_type_to_str(mem_type));
switch ( mem_type ) {
case MEMPROT_IRAM0_SRAM:
memprot_ll_iram0_set_monitor_en(enable);
break;
case MEMPROT_DRAM0_SRAM:
memprot_ll_dram0_set_monitor_en(enable);
break;
default:
ESP_EARLY_LOGE(TAG, "Invalid mem_type (%s), aborting", esp_memprot_mem_type_to_str(mem_type));
abort();
}
}
bool esp_memprot_get_monitor_en(mem_type_prot_t mem_type)
{
ESP_EARLY_LOGD(TAG, "esp_memprot_set_monitor_en(%s)", esp_memprot_mem_type_to_str(mem_type));
switch ( mem_type ) {
case MEMPROT_IRAM0_SRAM:
return memprot_ll_iram0_get_monitor_en();
case MEMPROT_DRAM0_SRAM:
return memprot_ll_dram0_get_monitor_en();
default:
ESP_EARLY_LOGE(TAG, "Invalid mem_type (%s), aborting", esp_memprot_mem_type_to_str(mem_type));
abort();
}
}
bool esp_memprot_is_intr_ena_any()
{
return esp_memprot_get_monitor_en(MEMPROT_IRAM0_SRAM) || esp_memprot_get_monitor_en(MEMPROT_DRAM0_SRAM);
}
void esp_memprot_monitor_clear_intr(mem_type_prot_t mem_type)
{
ESP_EARLY_LOGD(TAG, "esp_memprot_monitor_clear_intr(%s)", esp_memprot_mem_type_to_str(mem_type));
switch ( mem_type ) {
case MEMPROT_IRAM0_SRAM:
memprot_ll_iram0_clear_monitor_intr();
memprot_ll_iram0_reset_clear_monitor_intr();
break;
case MEMPROT_DRAM0_SRAM:
memprot_ll_dram0_clear_monitor_intr();
memprot_ll_dram0_reset_clear_monitor_intr();
break;
default:
ESP_EARLY_LOGE(TAG, "Invalid mem_type (%s), aborting", esp_memprot_mem_type_to_str(mem_type));
abort();
}
}
mem_type_prot_t esp_memprot_get_active_intr_memtype()
{
if ( memprot_ll_iram0_get_monitor_status_intr() > 0 ) {
return MEMPROT_IRAM0_SRAM;
} else if ( memprot_ll_dram0_get_monitor_status_intr() ) {
return MEMPROT_DRAM0_SRAM;
}
return MEMPROT_NONE;
}
bool esp_memprot_is_locked_any()
{
return
esp_memprot_get_split_line_lock() ||
esp_memprot_get_pms_lock(MEMPROT_IRAM0_SRAM) ||
esp_memprot_get_pms_lock(MEMPROT_DRAM0_SRAM) ||
esp_memprot_get_monitor_lock(MEMPROT_IRAM0_SRAM) ||
esp_memprot_get_monitor_lock(MEMPROT_DRAM0_SRAM);
}
bool esp_memprot_get_violate_intr_on(mem_type_prot_t mem_type)
{
switch ( mem_type ) {
case MEMPROT_IRAM0_SRAM:
return memprot_ll_iram0_get_monitor_status_intr() == 1;
case MEMPROT_DRAM0_SRAM:
return memprot_ll_dram0_get_monitor_status_intr() == 1;
default:
ESP_EARLY_LOGE(TAG, "Invalid mem_type (%s), aborting", esp_memprot_mem_type_to_str(mem_type));
abort();
}
}
uint32_t esp_memprot_get_violate_addr(mem_type_prot_t mem_type)
{
switch ( mem_type ) {
case MEMPROT_IRAM0_SRAM:
return memprot_ll_iram0_get_monitor_status_fault_addr();
case MEMPROT_DRAM0_SRAM:
return memprot_ll_dram0_get_monitor_status_fault_addr();
default:
ESP_EARLY_LOGE(TAG, "Invalid mem_type (%s), aborting", esp_memprot_mem_type_to_str(mem_type));
abort();
}
}
pms_world_t esp_memprot_get_violate_world(mem_type_prot_t mem_type)
{
uint32_t world = 0;
switch ( mem_type ) {
case MEMPROT_IRAM0_SRAM:
world = memprot_ll_iram0_get_monitor_status_fault_world();
break;
case MEMPROT_DRAM0_SRAM:
world = memprot_ll_dram0_get_monitor_status_fault_world();
break;
default:
ESP_EARLY_LOGE(TAG, "Invalid mem_type (%s), aborting", esp_memprot_mem_type_to_str(mem_type));
abort();
}
switch ( world ) {
case 0x01: return MEMPROT_PMS_WORLD_0;
case 0x10: return MEMPROT_PMS_WORLD_1;
default: return MEMPROT_PMS_WORLD_INVALID;
}
}
pms_operation_type_t esp_memprot_get_violate_wr(mem_type_prot_t mem_type)
{
switch ( mem_type ) {
case MEMPROT_IRAM0_SRAM:
return memprot_ll_iram0_get_monitor_status_fault_wr() == 1 ? MEMPROT_PMS_OP_WRITE : MEMPROT_PMS_OP_READ;
case MEMPROT_DRAM0_SRAM:
return memprot_ll_dram0_get_monitor_status_fault_wr() == 1 ? MEMPROT_PMS_OP_WRITE : MEMPROT_PMS_OP_READ;
default:
ESP_EARLY_LOGE(TAG, "Invalid mem_type (%s), aborting", esp_memprot_mem_type_to_str(mem_type));
abort();
}
}
bool esp_memprot_get_violate_loadstore(mem_type_prot_t mem_type)
{
switch ( mem_type ) {
case MEMPROT_IRAM0_SRAM:
return memprot_ll_iram0_get_monitor_status_fault_loadstore() == 1;
default:
ESP_EARLY_LOGE(TAG, "Invalid mem_type (%s), aborting", esp_memprot_mem_type_to_str(mem_type));
abort();
}
}
uint32_t esp_memprot_get_violate_byte_en(mem_type_prot_t mem_type)
{
switch ( mem_type ) {
case MEMPROT_DRAM0_SRAM:
return memprot_ll_dram0_get_monitor_status_fault_byte_en();
default:
ESP_EARLY_LOGE(TAG, "Invalid mem_type (%s), aborting", esp_memprot_mem_type_to_str(mem_type));
abort();
}
}
int esp_memprot_intr_get_cpuid()
{
return PRO_CPU_NUM;
}
void esp_memprot_set_intr_matrix(mem_type_prot_t mem_type)
{
ESP_EARLY_LOGD(TAG, "esp_memprot_set_intr_matrix(%s)", esp_memprot_mem_type_to_str(mem_type));
ESP_INTR_DISABLE(ETS_MEMPROT_ERR_INUM);
switch (mem_type) {
case MEMPROT_IRAM0_SRAM:
intr_matrix_set(esp_memprot_intr_get_cpuid(), memprot_ll_iram0_get_intr_source_num(), ETS_MEMPROT_ERR_INUM);
break;
case MEMPROT_DRAM0_SRAM:
intr_matrix_set(esp_memprot_intr_get_cpuid(), memprot_ll_dram0_get_intr_source_num(), ETS_MEMPROT_ERR_INUM);
break;
default:
ESP_EARLY_LOGE(TAG, "Invalid mem_type (%s), aborting", esp_memprot_mem_type_to_str(mem_type));
abort();
}
/* Set the type and priority to cache error interrupts. */
esprv_intc_int_set_type(BIT(ETS_MEMPROT_ERR_INUM), INTR_TYPE_LEVEL);
esprv_intc_int_set_priority(ETS_MEMPROT_ERR_INUM, SOC_INTERRUPT_LEVEL_MEDIUM);
ESP_INTR_ENABLE(ETS_MEMPROT_ERR_INUM);
}
void esp_memprot_set_prot(bool invoke_panic_handler, bool lock_feature, uint32_t *mem_type_mask)
{
esp_memprot_set_prot_int(invoke_panic_handler, lock_feature, NULL, mem_type_mask);
}
void esp_memprot_set_prot_int(bool invoke_panic_handler, bool lock_feature, void *split_addr, uint32_t *mem_type_mask)
{
ESP_EARLY_LOGD(TAG, "esp_memprot_set_prot(panic_handler: %u, lock: %u, split.addr: 0x%08X, mem.types: 0x%08X", invoke_panic_handler, lock_feature, (uint32_t)split_addr, (uint32_t)mem_type_mask);
uint32_t required_mem_prot = mem_type_mask == NULL ? (uint32_t)MEMPROT_ALL : *mem_type_mask;
bool use_iram0 = required_mem_prot & MEMPROT_IRAM0_SRAM;
bool use_dram0 = required_mem_prot & MEMPROT_DRAM0_SRAM;
if (required_mem_prot == MEMPROT_NONE) {
return;
}
//disable protection
if (use_iram0) {
esp_memprot_set_monitor_en(MEMPROT_IRAM0_SRAM, false);
}
if (use_dram0) {
esp_memprot_set_monitor_en(MEMPROT_DRAM0_SRAM, false);
}
//panic handling
if (invoke_panic_handler) {
if (use_iram0) {
esp_memprot_set_intr_matrix(MEMPROT_IRAM0_SRAM);
}
if (use_dram0) {
esp_memprot_set_intr_matrix(MEMPROT_DRAM0_SRAM);
}
}
//set split lines (must-have for all mem_types)
const void *line_addr = split_addr == NULL ? esp_memprot_get_default_main_split_addr() : split_addr;
esp_memprot_set_split_line(MEMPROT_IRAM0_LINE_1_SPLITLINE, line_addr);
esp_memprot_set_split_line(MEMPROT_IRAM0_LINE_0_SPLITLINE, line_addr);
esp_memprot_set_split_line(MEMPROT_IRAM0_DRAM0_SPLITLINE, line_addr);
esp_memprot_set_split_line(MEMPROT_DRAM0_DMA_LINE_0_SPLITLINE, (void *)(MAP_IRAM_TO_DRAM((uint32_t)line_addr)));
esp_memprot_set_split_line(MEMPROT_DRAM0_DMA_LINE_1_SPLITLINE, (void *)(MAP_IRAM_TO_DRAM((uint32_t)line_addr)));
//set permissions
if (required_mem_prot & MEMPROT_IRAM0_SRAM) {
esp_memprot_iram_set_pms_area(MEMPROT_IRAM0_PMS_AREA_0, true, false, true);
esp_memprot_iram_set_pms_area(MEMPROT_IRAM0_PMS_AREA_1, true, false, true);
esp_memprot_iram_set_pms_area(MEMPROT_IRAM0_PMS_AREA_2, true, false, true);
esp_memprot_iram_set_pms_area(MEMPROT_IRAM0_PMS_AREA_3, true, true, false);
}
if (required_mem_prot & MEMPROT_DRAM0_SRAM) {
esp_memprot_dram_set_pms_area( MEMPROT_DRAM0_PMS_AREA_0, true, false );
esp_memprot_dram_set_pms_area(MEMPROT_DRAM0_PMS_AREA_1, true, true);
esp_memprot_dram_set_pms_area(MEMPROT_DRAM0_PMS_AREA_2, true, true);
esp_memprot_dram_set_pms_area(MEMPROT_DRAM0_PMS_AREA_3, true, true);
}
//reenable protection
if (use_iram0) {
esp_memprot_monitor_clear_intr(MEMPROT_IRAM0_SRAM);
esp_memprot_set_monitor_en(MEMPROT_IRAM0_SRAM, true);
}
if (use_dram0) {
esp_memprot_monitor_clear_intr(MEMPROT_DRAM0_SRAM);
esp_memprot_set_monitor_en(MEMPROT_DRAM0_SRAM, true);
}
//lock if required
if (lock_feature) {
esp_memprot_set_split_line_lock();
if (use_iram0) {
esp_memprot_set_pms_lock(MEMPROT_IRAM0_SRAM);
esp_memprot_set_monitor_lock(MEMPROT_IRAM0_SRAM);
}
if (use_dram0) {
esp_memprot_set_pms_lock(MEMPROT_DRAM0_SRAM);
esp_memprot_set_monitor_lock(MEMPROT_DRAM0_SRAM);
}
}
}
uint32_t esp_memprot_get_dram_status_reg_1()
{
return memprot_ll_dram0_get_monitor_status_register_1();
}
uint32_t esp_memprot_get_dram_status_reg_2()
{
return memprot_ll_dram0_get_monitor_status_register_2();
}
uint32_t esp_memprot_get_iram_status_reg()
{
return memprot_ll_iram0_get_monitor_status_register();
}
uint32_t esp_memprot_get_monitor_enable_reg(mem_type_prot_t mem_type)
{
switch (mem_type) {
case MEMPROT_IRAM0_SRAM:
return memprot_ll_iram0_get_monitor_enable_register();
case MEMPROT_DRAM0_SRAM:
return memprot_ll_dram0_get_monitor_enable_register();
default:
abort();
}
}

View File

@ -0,0 +1,5 @@
set(compile_options "-Wno-error=format="
"-nostartfiles"
"-Wno-format")
idf_build_set_property(COMPILE_OPTIONS "${compile_options}" APPEND)

View File

@ -0,0 +1,9 @@
if(IDF_TARGET STREQUAL "esp32c3")
idf_component_register(SRC_DIRS .
INCLUDE_DIRS . ${CMAKE_CURRENT_BINARY_DIR}
REQUIRES unity test_utils esp_common mbedtls
)
idf_build_set_property(COMPILE_DEFINITIONS "-DESP_TIMER_DYNAMIC_OVERFLOW_VAL" APPEND)
target_link_libraries(${COMPONENT_LIB} INTERFACE "-u ld_include_test_dport_xt_highint5")
endif()

View File

@ -0,0 +1,4 @@
#
# Component Makefile (not used for tests, but CI checks test parity between GNU Make & CMake)
#
COMPONENT_CONFIG_ONLY := 1

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,382 @@
// 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 "unity.h"
#include "esp32c3/rom/efuse.h"
#include "esp32c3/rom/digital_signature.h"
#include "esp32c3/rom/hmac.h"
#include <string.h>
#include "esp_ds.h"
#define NUM_RESULTS 10
#define DS_MAX_BITS (ETS_DS_MAX_BITS)
typedef struct {
uint8_t iv[ETS_DS_IV_LEN];
ets_ds_p_data_t p_data;
uint8_t expected_c[ETS_DS_C_LEN];
uint8_t hmac_key_idx;
uint32_t expected_results[NUM_RESULTS][DS_MAX_BITS/32];
} encrypt_testcase_t;
// Generated header (components/esp32s2/test/gen_digital_signature_tests.py) defines
// NUM_HMAC_KEYS, test_hmac_keys, NUM_MESSAGES, NUM_CASES, test_messages[], test_cases[]
#include "digital_signature_test_cases.h"
_Static_assert(NUM_RESULTS == NUM_MESSAGES, "expected_results size should be the same as NUM_MESSAGES in generated header");
TEST_CASE("Digital Signature Parameter Encryption data NULL", "[hw_crypto] [ds]")
{
const char iv [32];
esp_ds_p_data_t p_data;
const char key [32];
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_encrypt_params(NULL, iv, &p_data, key));
}
TEST_CASE("Digital Signature Parameter Encryption iv NULL", "[hw_crypto] [ds]")
{
esp_ds_data_t data;
esp_ds_p_data_t p_data;
const char key [32];
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_encrypt_params(&data, NULL, &p_data, key));
}
TEST_CASE("Digital Signature Parameter Encryption p_data NULL", "[hw_crypto] [ds]")
{
esp_ds_data_t data;
const char iv [32];
const char key [32];
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_encrypt_params(&data, iv, NULL, key));
}
TEST_CASE("Digital Signature Parameter Encryption key NULL", "[hw_crypto] [ds]")
{
esp_ds_data_t data;
const char iv [32];
esp_ds_p_data_t p_data;
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_encrypt_params(&data, iv, &p_data, NULL));
}
TEST_CASE("Digital Signature Parameter Encryption", "[hw_crypto] [ds]")
{
for (int i = 0; i < NUM_CASES; i++) {
printf("Encrypting test case %d...\n", i);
const encrypt_testcase_t *t = &test_cases[i];
esp_ds_data_t result = { };
esp_ds_p_data_t p_data;
memcpy(p_data.Y, t->p_data.Y, ESP_DS_SIGNATURE_MAX_BIT_LEN/8);
memcpy(p_data.M, t->p_data.M, ESP_DS_SIGNATURE_MAX_BIT_LEN/8);
memcpy(p_data.Rb, t->p_data.Rb, ESP_DS_SIGNATURE_MAX_BIT_LEN/8);
p_data.M_prime = t->p_data.M_prime;
p_data.length = t->p_data.length;
esp_err_t r = esp_ds_encrypt_params(&result, t->iv, &p_data,
test_hmac_keys[t->hmac_key_idx]);
printf("Encrypting test case %d done\n", i);
TEST_ASSERT_EQUAL(ESP_OK, r);
TEST_ASSERT_EQUAL(t->p_data.length, result.rsa_length);
TEST_ASSERT_EQUAL_HEX8_ARRAY(t->iv, result.iv, ETS_DS_IV_LEN);
TEST_ASSERT_EQUAL_HEX8_ARRAY(t->expected_c, result.c, ETS_DS_C_LEN);
}
}
TEST_CASE("Digital Signature start Invalid message", "[hw_crypto] [ds]")
{
esp_ds_data_t ds_data = { };
ds_data.rsa_length = ESP_DS_RSA_3072;
esp_ds_context_t *ctx;
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_start_sign(NULL, &ds_data, HMAC_KEY1, &ctx));
}
TEST_CASE("Digital Signature start Invalid data", "[hw_crypto] [ds]")
{
const char *message = "test";
esp_ds_context_t *ctx;
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_start_sign(message, NULL, HMAC_KEY1, &ctx));
}
TEST_CASE("Digital Signature start Invalid context", "[hw_crypto] [ds]")
{
esp_ds_data_t ds_data = {};
ds_data.rsa_length = ESP_DS_RSA_3072;
const char *message = "test";
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_start_sign(message, &ds_data, HMAC_KEY1, NULL));
}
TEST_CASE("Digital Signature RSA length 0", "[hw_crypto] [ds]")
{
esp_ds_data_t ds_data = {};
ds_data.rsa_length = 0;
const char *message = "test";
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_start_sign(message, &ds_data, HMAC_KEY1, NULL));
}
TEST_CASE("Digital Signature RSA length too long", "[hw_crypto] [ds]")
{
esp_ds_data_t ds_data = {};
ds_data.rsa_length = 128;
const char *message = "test";
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_start_sign(message, &ds_data, HMAC_KEY1, NULL));
}
TEST_CASE("Digital Signature start HMAC key out of range", "[hw_crypto] [ds]")
{
esp_ds_data_t ds_data = {};
ds_data.rsa_length = ESP_DS_RSA_3072;
esp_ds_context_t *ctx;
const char *message = "test";
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_start_sign(message, &ds_data, HMAC_KEY5 + 1, &ctx));
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_start_sign(message, &ds_data, HMAC_KEY0 - 1, &ctx));
}
TEST_CASE("Digital Signature finish Invalid signature ptr", "[hw_crypto] [ds]")
{
esp_ds_context_t *ctx = NULL;
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_finish_sign(NULL, ctx));
}
TEST_CASE("Digital Signature finish Invalid context", "[hw_crypto] [ds]")
{
uint8_t signature_data [128 * 4];
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_finish_sign(signature_data, NULL));
}
TEST_CASE("Digital Signature Blocking Invalid message", "[hw_crypto] [ds]")
{
esp_ds_data_t ds_data = { };
ds_data.rsa_length = ESP_DS_RSA_3072;
uint8_t signature_data [128 * 4];
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_sign(NULL, &ds_data, HMAC_KEY1, signature_data));
}
TEST_CASE("Digital Signature Blocking Invalid data", "[hw_crypto] [ds]")
{
const char *message = "test";
uint8_t signature_data [128 * 4];
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_sign(message, NULL, HMAC_KEY1, signature_data));
}
TEST_CASE("Digital Signature Blocking Invalid signature ptr", "[hw_crypto] [ds]")
{
esp_ds_data_t ds_data = {};
ds_data.rsa_length = ESP_DS_RSA_3072;
const char *message = "test";
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_sign(message, &ds_data, HMAC_KEY1, NULL));
}
TEST_CASE("Digital Signature Blocking RSA length 0", "[hw_crypto] [ds]")
{
esp_ds_data_t ds_data = {};
ds_data.rsa_length = 0;
const char *message = "test";
uint8_t signature_data [128 * 4];
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_sign(message, &ds_data, HMAC_KEY1, signature_data));
}
TEST_CASE("Digital Signature Blocking RSA length too long", "[hw_crypto] [ds]")
{
esp_ds_data_t ds_data = {};
ds_data.rsa_length = 128;
const char *message = "test";
uint8_t signature_data [128 * 4];
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_sign(message, &ds_data, HMAC_KEY1, signature_data));
}
TEST_CASE("Digital Signature Blocking HMAC key out of range", "[hw_crypto] [ds]")
{
esp_ds_data_t ds_data = {};
ds_data.rsa_length = 127;
const char *message = "test";
uint8_t signature_data [128 * 4];
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_sign(message, &ds_data, HMAC_KEY5 + 1, signature_data));
TEST_ASSERT_EQUAL(ESP_ERR_INVALID_ARG, esp_ds_sign(message, &ds_data, HMAC_KEY0 - 1, signature_data));
}
#if CONFIG_IDF_ENV_FPGA
// Burn eFuse blocks 1, 2 and 3. Block 0 is used for HMAC tests already.
static void burn_hmac_keys(void)
{
printf("Burning %d HMAC keys to efuse...\n", NUM_HMAC_KEYS);
for (int i = 0; i < NUM_HMAC_KEYS; i++) {
// TODO: vary the purpose across the keys
ets_efuse_purpose_t purpose = ETS_EFUSE_KEY_PURPOSE_HMAC_DOWN_DIGITAL_SIGNATURE;
ets_efuse_write_key(ETS_EFUSE_BLOCK_KEY1 + i,
purpose,
test_hmac_keys[i], 32);
}
/* verify the keys are what we expect (possibly they're already burned, doesn't matter but they have to match) */
uint8_t block_compare[32];
for (int i = 0; i < NUM_HMAC_KEYS; i++) {
printf("Checking key %d...\n", i);
memcpy(block_compare, (void *)ets_efuse_get_read_register_address(ETS_EFUSE_BLOCK_KEY1 + i), 32);
TEST_ASSERT_EQUAL_HEX8_ARRAY(test_hmac_keys[i], block_compare, 32);
}
}
// This test uses the HMAC_KEY0 eFuse key which hasn't been burned by burn_hmac_keys().
// HMAC_KEY0 is usually used for HMAC upstream (user access) tests.
TEST_CASE("Digital Signature wrong HMAC key purpose (FPGA only)", "[hw_crypto] [ds]")
{
esp_ds_data_t ds_data = {};
ds_data.rsa_length = ESP_DS_RSA_3072;
esp_ds_context_t *ctx;
const char *message = "test";
// HMAC fails in that case because it checks for the correct purpose
TEST_ASSERT_EQUAL(ESP32C3_ERR_HW_CRYPTO_DS_HMAC_FAIL, esp_ds_start_sign(message, &ds_data, HMAC_KEY0, &ctx));
}
// This test uses the HMAC_KEY0 eFuse key which hasn't been burned by burn_hmac_keys().
// HMAC_KEY0 is usually used for HMAC upstream (user access) tests.
TEST_CASE("Digital Signature Blocking wrong HMAC key purpose (FPGA only)", "[hw_crypto] [ds]")
{
esp_ds_data_t ds_data = {};
ds_data.rsa_length = ESP_DS_RSA_3072;
const char *message = "test";
uint8_t signature_data [128 * 4];
// HMAC fails in that case because it checks for the correct purpose
TEST_ASSERT_EQUAL(ESP32C3_ERR_HW_CRYPTO_DS_HMAC_FAIL, esp_ds_sign(message, &ds_data, HMAC_KEY0, signature_data));
}
TEST_CASE("Digital Signature Operation (FPGA only)", "[hw_crypto] [ds]")
{
burn_hmac_keys();
for (int i = 0; i < NUM_CASES; i++) {
printf("Running test case %d...\n", i);
const encrypt_testcase_t *t = &test_cases[i];
// copy encrypt parameter test case into ds_data structure
esp_ds_data_t ds_data = { };
memcpy(ds_data.iv, t->iv, ETS_DS_IV_LEN);
memcpy(ds_data.c, t->expected_c, ETS_DS_C_LEN);
ds_data.rsa_length = t->p_data.length;
for (int j = 0; j < NUM_MESSAGES; j++) {
uint8_t signature[DS_MAX_BITS/8] = { 0 };
printf(" ... message %d\n", j);
esp_ds_context_t *esp_ds_ctx;
esp_err_t ds_r = esp_ds_start_sign(test_messages[j],
&ds_data,
t->hmac_key_idx + 1,
&esp_ds_ctx);
TEST_ASSERT_EQUAL(ESP_OK, ds_r);
ds_r = esp_ds_finish_sign(signature, esp_ds_ctx);
TEST_ASSERT_EQUAL(ESP_OK, ds_r);
TEST_ASSERT_EQUAL_HEX8_ARRAY(t->expected_results[j], signature, sizeof(signature));
}
ets_hmac_invalidate_downstream(ETS_EFUSE_KEY_PURPOSE_HMAC_DOWN_DIGITAL_SIGNATURE);
}
}
TEST_CASE("Digital Signature Blocking Operation (FPGA only)", "[hw_crypto] [ds]")
{
burn_hmac_keys();
for (int i = 0; i < NUM_CASES; i++) {
printf("Running test case %d...\n", i);
const encrypt_testcase_t *t = &test_cases[i];
// copy encrypt parameter test case into ds_data structure
esp_ds_data_t ds_data = { };
memcpy(ds_data.iv, t->iv, ETS_DS_IV_LEN);
memcpy(ds_data.c, t->expected_c, ETS_DS_C_LEN);
ds_data.rsa_length = t->p_data.length;
uint8_t signature[DS_MAX_BITS/8] = { 0 };
esp_err_t ds_r = esp_ds_sign(test_messages[0],
&ds_data,
t->hmac_key_idx + 1,
signature);
TEST_ASSERT_EQUAL(ESP_OK, ds_r);
TEST_ASSERT_EQUAL_HEX8_ARRAY(t->expected_results[0], signature, sizeof(signature));
}
}
TEST_CASE("Digital Signature Invalid Data (FPGA only)", "[hw_crypto] [ds]")
{
burn_hmac_keys();
// Set up a valid test case
const encrypt_testcase_t *t = &test_cases[0];
esp_ds_data_t ds_data = { };
memcpy(ds_data.iv, t->iv, ETS_DS_IV_LEN);
memcpy(ds_data.c, t->expected_c, ETS_DS_C_LEN);
ds_data.rsa_length = t->p_data.length;
uint8_t signature[DS_MAX_BITS/8] = { 0 };
const uint8_t zero[DS_MAX_BITS/8] = { 0 };
// Corrupt the IV one bit at a time, rerun and expect failure
for (int bit = 0; bit < 128; bit++) {
printf("Corrupting IV bit %d...\n", bit);
ds_data.iv[bit / 8] ^= 1 << (bit % 8);
esp_ds_context_t *esp_ds_ctx;
esp_err_t ds_r = esp_ds_start_sign(test_messages[0], &ds_data, t->hmac_key_idx + 1, &esp_ds_ctx);
TEST_ASSERT_EQUAL(ESP_OK, ds_r);
ds_r = esp_ds_finish_sign(signature, esp_ds_ctx);
TEST_ASSERT_EQUAL(ESP32C3_ERR_HW_CRYPTO_DS_INVALID_DIGEST, ds_r);
TEST_ASSERT_EQUAL_HEX8_ARRAY(zero, signature, DS_MAX_BITS/8);
ds_data.iv[bit / 8] ^= 1 << (bit % 8);
}
// Corrupt encrypted key data one bit at a time, rerun and expect failure
printf("Corrupting C...\n");
for (int bit = 0; bit < ETS_DS_C_LEN * 8; bit++) {
printf("Corrupting C bit %d...\n", bit);
ds_data.c[bit / 8] ^= 1 << (bit % 8);
esp_ds_context_t *esp_ds_ctx;
esp_err_t ds_r = esp_ds_start_sign(test_messages[0], &ds_data, t->hmac_key_idx + 1, &esp_ds_ctx);
TEST_ASSERT_EQUAL(ESP_OK, ds_r);
ds_r = esp_ds_finish_sign(signature, esp_ds_ctx);
TEST_ASSERT_EQUAL(ESP32C3_ERR_HW_CRYPTO_DS_INVALID_DIGEST, ds_r);
TEST_ASSERT_EQUAL_HEX8_ARRAY(zero, signature, DS_MAX_BITS/8);
ds_data.c[bit / 8] ^= 1 << (bit % 8);
}
}
#endif // CONFIG_IDF_ENV_FPGA

View File

@ -0,0 +1,80 @@
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include "esp_types.h"
#include "esp32c3/clk.h"
#include "esp_log.h"
#include "esp_timer.h"
#include "esp_heap_caps.h"
#include "idf_performance.h"
#include "unity.h"
#include "test_utils.h"
#include "mbedtls/sha1.h"
#include "mbedtls/sha256.h"
#include "sha/sha_dma.h"
/* Note: Most of the SHA functions are called as part of mbedTLS, so
are tested as part of mbedTLS tests. Only esp_sha() is different.
*/
#define TAG "sha_test"
TEST_CASE("Test esp_sha()", "[hw_crypto]")
{
const size_t BUFFER_SZ = 32 * 1024 + 6; // NB: not an exact multiple of SHA block size
int64_t begin, end;
uint32_t us_sha1;
uint8_t sha1_result[20] = { 0 };
void *buffer = heap_caps_malloc(BUFFER_SZ, MALLOC_CAP_8BIT|MALLOC_CAP_INTERNAL);
TEST_ASSERT_NOT_NULL(buffer);
memset(buffer, 0xEE, BUFFER_SZ);
const uint8_t sha1_expected[20] = { 0xc7, 0xbb, 0xd3, 0x74, 0xf2, 0xf6, 0x20, 0x86,
0x61, 0xf4, 0x50, 0xd5, 0xf5, 0x18, 0x44, 0xcc,
0x7a, 0xb7, 0xa5, 0x4a };
begin = esp_timer_get_time();
esp_sha(SHA1, buffer, BUFFER_SZ, sha1_result);
end = esp_timer_get_time();
TEST_ASSERT_EQUAL_HEX8_ARRAY(sha1_expected, sha1_result, sizeof(sha1_expected));
us_sha1 = end - begin;
ESP_LOGI(TAG, "esp_sha() 32KB SHA1 in %u us", us_sha1);
free(buffer);
TEST_PERFORMANCE_CCOMP_LESS_THAN(TIME_SHA1_32KB, "%dus", us_sha1);
}
TEST_CASE("Test esp_sha() function with long input", "[hw_crypto]")
{
const void* ptr;
spi_flash_mmap_handle_t handle;
uint8_t sha1_espsha[20] = { 0 };
uint8_t sha1_mbedtls[20] = { 0 };
uint8_t sha256_espsha[32] = { 0 };
uint8_t sha256_mbedtls[32] = { 0 };
const size_t LEN = 1024 * 1024;
/* mmap() 1MB of flash, we don't care what it is really */
esp_err_t err = spi_flash_mmap(0x0, LEN, SPI_FLASH_MMAP_DATA, &ptr, &handle);
TEST_ASSERT_EQUAL_HEX32(ESP_OK, err);
TEST_ASSERT_NOT_NULL(ptr);
/* Compare esp_sha() result to the mbedTLS result, should always be the same */
esp_sha(SHA1, ptr, LEN, sha1_espsha);
int r = mbedtls_sha1_ret(ptr, LEN, sha1_mbedtls);
TEST_ASSERT_EQUAL(0, r);
esp_sha(SHA2_256, ptr, LEN, sha256_espsha);
r = mbedtls_sha256_ret(ptr, LEN, sha256_mbedtls, 0);
TEST_ASSERT_EQUAL(0, r);
TEST_ASSERT_EQUAL_MEMORY_MESSAGE(sha1_espsha, sha1_mbedtls, sizeof(sha1_espsha), "SHA1 results should match");
TEST_ASSERT_EQUAL_MEMORY_MESSAGE(sha256_espsha, sha256_mbedtls, sizeof(sha256_espsha), "SHA256 results should match");
}

View File

@ -0,0 +1,165 @@
// 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.
// The HAL layer for ADC (ESP32-C3 specific part)
#include <string.h>
#include "soc/soc_caps.h"
#include "hal/adc_hal.h"
#include "hal/adc_types.h"
#include "soc/soc.h"
//Currently we don't have context for the ADC HAL. So HAL variables are temporarily put here. But
//please don't follow this code. Create a context for your own HAL!
static bool s_filter_enabled[SOC_ADC_DIGI_FILTER_NUM] = {};
static adc_digi_filter_t s_filter[SOC_ADC_DIGI_FILTER_NUM] = {};
static bool s_monitor_enabled[SOC_ADC_DIGI_MONITOR_NUM] = {};
static adc_digi_monitor_t s_monitor_config[SOC_ADC_DIGI_MONITOR_NUM] = {};
/*---------------------------------------------------------------
Digital controller setting
---------------------------------------------------------------*/
void adc_hal_digi_deinit(void)
{
adc_ll_digi_trigger_disable(); // boss
adc_ll_digi_dma_disable();
adc_ll_digi_clear_pattern_table(ADC_NUM_1);
adc_ll_digi_clear_pattern_table(ADC_NUM_2);
adc_ll_digi_filter_reset(ADC_NUM_1);
adc_ll_digi_filter_reset(ADC_NUM_2);
adc_ll_digi_reset();
adc_ll_digi_controller_clk_disable();
}
/**
* - Set ADC digital controller clock division factor. The clock is divided from `APLL` or `APB` clock.
* Expression: controller_clk = APLL/APB * (div_num + div_a / div_b + 1).
* - Enable clock and select clock source for ADC digital controller.
*/
static void adc_hal_digi_clk_config(void)
{
//Here we set the clock divider factor to make the digital clock to 5M Hz
adc_ll_digi_controller_clk_div(ADC_LL_CLKM_DIV_NUM_DEFAULT, ADC_LL_CLKM_DIV_B_DEFAULT, ADC_LL_CLKM_DIV_A_DEFAULT);
adc_ll_digi_controller_clk_enable(0);
}
void adc_hal_digi_controller_config(const adc_digi_config_t *cfg)
{
//only one pattern table is supported on C3, but LL still needs one argument.
const int pattern_both = 0;
if (cfg->adc_pattern_len) {
adc_ll_digi_clear_pattern_table(pattern_both);
adc_ll_digi_set_pattern_table_len(pattern_both, cfg->adc_pattern_len);
for (uint32_t i = 0; i < cfg->adc_pattern_len; i++) {
adc_ll_digi_set_pattern_table(pattern_both, i, cfg->adc_pattern[i]);
}
}
if (cfg->conv_limit_en) {
adc_ll_digi_set_convert_limit_num(cfg->conv_limit_num);
adc_ll_digi_convert_limit_enable();
} else {
adc_ll_digi_convert_limit_disable();
}
//clock
uint32_t interval = APB_CLK_FREQ / (ADC_LL_CLKM_DIV_NUM_DEFAULT + ADC_LL_CLKM_DIV_A_DEFAULT / ADC_LL_CLKM_DIV_B_DEFAULT + 1) / 2 / cfg->sample_freq_hz;
adc_ll_digi_set_trigger_interval(interval);
adc_hal_digi_clk_config();
}
static void filter_update(adc_digi_filter_idx_t idx)
{
//ESP32-C3 has no enable bit, the filter will be enabled when the filter channel is configured
if (s_filter_enabled[idx]) {
adc_ll_digi_filter_set_factor(idx, &s_filter[idx]);
} else {
adc_ll_digi_filter_disable(idx);
}
}
/**
* Set adc digital controller filter factor.
*
* @param idx ADC filter unit.
* @param filter Filter config. Expression: filter_data = (k-1)/k * last_data + new_data / k. Set values: (2, 4, 8, 16, 64).
*/
void adc_hal_digi_filter_set_factor(adc_digi_filter_idx_t idx, adc_digi_filter_t *filter)
{
s_filter[idx] = *filter;
filter_update(idx);
}
/**
* Get adc digital controller filter factor.
*
* @param adc_n ADC unit.
* @param factor Expression: filter_data = (k-1)/k * last_data + new_data / k. Set values: (2, 4, 8, 16, 64).
*/
void adc_hal_digi_filter_get_factor(adc_digi_filter_idx_t idx, adc_digi_filter_t *filter)
{
*filter = s_filter[idx];
}
void adc_hal_digi_filter_enable(adc_digi_filter_idx_t filter_idx, bool enable)
{
s_filter_enabled[filter_idx] = enable;
filter_update(filter_idx);
}
static void update_monitor(adc_digi_monitor_idx_t idx)
{
//ESP32-C3 has no enable bit, the monitor will be enabled when the monitor channel is configured
if (s_monitor_enabled[idx]) {
adc_ll_digi_monitor_set_mode(idx, &s_monitor_config[idx]);
} else {
adc_ll_digi_monitor_disable(idx);
}
}
void adc_hal_digi_monitor_config(adc_digi_monitor_idx_t idx, adc_digi_monitor_t *config)
{
s_monitor_config[idx] = *config;
update_monitor(idx);
}
void adc_hal_digi_monitor_enable(adc_digi_monitor_idx_t mon_idx, bool enable)
{
s_monitor_enabled[mon_idx] = enable;
update_monitor(mon_idx);
}
/*---------------------------------------------------------------
Common setting
---------------------------------------------------------------*/
/**
* Config ADC2 module arbiter.
* The arbiter is to improve the use efficiency of ADC2. After the control right is robbed by the high priority,
* the low priority controller will read the invalid ADC2 data, and the validity of the data can be judged by the flag bit in the data.
*
* @note Only ADC2 support arbiter.
* @note The arbiter's working clock is APB_CLK. When the APB_CLK clock drops below 8 MHz, the arbiter must be in shield mode.
* @note Default priority: Wi-Fi > RTC > Digital;
*
* @param config Refer to `adc_arbiter_t`.
*/
void adc_hal_arbiter_config(adc_arbiter_t *config)
{
adc_ll_set_arbiter_work_mode(config->mode);
adc_ll_set_arbiter_priority(config->rtc_pri, config->dig_pri, config->pwdet_pri);
}

View File

@ -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 "hal/brownout_hal.h"
#include "soc/rtc_cntl_struct.h"
#include "soc/rtc_cntl_reg.h"
#include "regi2c_ctrl.h"
#include "regi2c_brownout.h"
void brownout_hal_config(const brownout_hal_config_t *cfg)
{
REGI2C_WRITE_MASK(I2C_BOD, I2C_BOD_THRESHOLD, cfg->threshold);
typeof(RTCCNTL.brown_out) brown_out_reg = {
.close_flash_ena = cfg->flash_power_down,
.pd_rf_ena = cfg->rf_power_down,
.rst_wait = 0x3ff,
.rst_ena = cfg->reset_enabled,
.ena = cfg->enabled,
.rst_sel = 1,
};
RTCCNTL.brown_out = brown_out_reg;
}
void brownout_hal_intr_enable(bool enable)
{
RTCCNTL.int_ena.rtc_brown_out = enable;
}
void brownout_hal_intr_clear(void)
{
RTCCNTL.int_clr.rtc_brown_out = 1;
}

View File

@ -0,0 +1,83 @@
// 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 "stdio.h"
#include "hal/hmac_hal.h"
#include "hal/hmac_ll.h"
void hmac_hal_start(void)
{
hmac_ll_wait_idle();
hmac_ll_start();
}
uint32_t hmac_hal_configure(hmac_hal_output_t config, uint32_t key_id)
{
hmac_ll_wait_idle();
hmac_ll_config_output(config);
hmac_ll_config_hw_key_id(key_id);
hmac_ll_config_finish();
hmac_ll_wait_idle();
uint32_t conf_error = hmac_ll_config_error();
if (conf_error) {
hmac_ll_calc_finish();
return 1;
} else if (config != HMAC_OUTPUT_USER) {
// In "downstream" mode, this will be the last hmac operation. Make sure HMAC is ready for
// the other peripheral.
hmac_ll_wait_idle();
}
return 0;
}
void hmac_hal_write_one_block_512(const void *block)
{
hmac_ll_wait_idle();
hmac_ll_write_block_512(block);
hmac_ll_wait_idle();
hmac_ll_msg_one_block();
}
void hmac_hal_write_block_512(const void *block)
{
hmac_ll_wait_idle();
hmac_ll_write_block_512(block);
}
void hmac_hal_next_block_padding(void)
{
hmac_ll_wait_idle();
hmac_ll_msg_padding();
}
void hmac_hal_next_block_normal(void)
{
hmac_ll_wait_idle();
hmac_ll_msg_continue();
}
void hmac_hal_read_result_256(void *result)
{
hmac_ll_wait_idle();
hmac_ll_read_result_256(result);
hmac_ll_calc_finish();
}
void hmac_hal_clean(void)
{
hmac_ll_wait_idle();
hmac_ll_clean();
}

View File

@ -0,0 +1,119 @@
// 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.
/*******************************************************************************
* NOTICE
* The hal is not public api, don't use in application code.
* See readme.md in soc/include/hal/readme.md
******************************************************************************/
// The HAL layer for ADC (esp32s2 specific part)
#pragma once
#include "hal/adc_ll.h"
#include "hal/adc_types.h"
#include_next "hal/adc_hal.h"
#ifdef __cplusplus
extern "C" {
#endif
/*---------------------------------------------------------------
Digital controller setting
---------------------------------------------------------------*/
/**
* Digital controller deinitialization.
*/
void adc_hal_digi_deinit(void);
/**
* Setting the digital controller.
*
* @param cfg Pointer to digital controller paramter.
*/
void adc_hal_digi_controller_config(const adc_digi_config_t *cfg);
/**
* Reset adc digital controller filter.
*
* @param filter_idx ADC filter unit.
*/
#define adc_hal_digi_filter_reset(filter_idx) adc_ll_digi_filter_reset(filter_idx)
/**
* Set adc digital controller filter factor.
*
* @param filter_idx ADC filter unit.
* @param filter Filter config. Expression: filter_data = (k-1)/k * last_data + new_data / k. Set values: (2, 4, 8, 16, 64).
*/
void adc_hal_digi_filter_set_factor(adc_digi_filter_idx_t filter_idx, adc_digi_filter_t *filter);
/**
* Get adc digital controller filter factor.
*
* @param filter_idx ADC filter unit.
* @param factor Expression: filter_data = (k-1)/k * last_data + new_data / k. Set values: (2, 4, 8, 16, 64).
*/
void adc_hal_digi_filter_get_factor(adc_digi_filter_idx_t filter_idx, adc_digi_filter_t *filter);
/**
* Enable/disable adc digital controller filter.
* Filtering the ADC data to obtain smooth data at higher sampling rates.
*
* @note The filter will filter all the enabled channel data of the each ADC unit at the same time.
* @param filter_idx ADC filter unit.
* @param enable True to enable the filter, otherwise disable.
*/
void adc_hal_digi_filter_enable(adc_digi_filter_idx_t filter_idx, bool enable);
/**
* Config monitor of adc digital controller.
*
* @note If the channel info is not supported, the monitor function will not be enabled.
* @param mon_idx ADC monitor index.
* @param config Refer to `adc_digi_monitor_t`.
*/
void adc_hal_digi_monitor_config(adc_digi_monitor_idx_t mon_idx, adc_digi_monitor_t *config);
/**
* Enable/disable monitor of adc digital controller.
*
* @note The monitor will monitor all the enabled channel data of the each ADC unit at the same time.
* @param mon_idx ADC monitor index.
* @param enable True to enable the monitor, otherwise disable.
*/
void adc_hal_digi_monitor_enable(adc_digi_monitor_idx_t mon_idx, bool enable);
/*---------------------------------------------------------------
Common setting
---------------------------------------------------------------*/
/**
* Config ADC2 module arbiter.
* The arbiter is to improve the use efficiency of ADC2. After the control right is robbed by the high priority,
* the low priority controller will read the invalid ADC2 data, and the validity of the data can be judged by the flag bit in the data.
*
* @note Only ADC2 support arbiter.
* @note The arbiter's working clock is APB_CLK. When the APB_CLK clock drops below 8 MHz, the arbiter must be in shield mode.
* @note Default priority: Wi-Fi > RTC > Digital;
*
* @param config Refer to `adc_arbiter_t`.
*/
void adc_hal_arbiter_config(adc_arbiter_t *config);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,31 @@
// 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
#define SOC_ADC1_DATA_INVERT_DEFAULT (0)
#define SOC_ADC2_DATA_INVERT_DEFAULT (0)
#define SOC_ADC_DIGI_DATA_INVERT_DEFAULT(PERIPH_NUM) (0)
#define SOC_ADC_FSM_RSTB_WAIT_DEFAULT (8)
#define SOC_ADC_FSM_START_WAIT_DEFAULT (5)
#define SOC_ADC_FSM_STANDBY_WAIT_DEFAULT (100)
#define ADC_FSM_SAMPLE_CYCLE_DEFAULT (2)
#define SOC_ADC_PWDET_CCT_DEFAULT (4)
#define SOC_ADC_SAR_CLK_DIV_DEFAULT(PERIPH_NUM) ((PERIPH_NUM==0)? 2 : 1)
#define SOC_ADC_DIGI_SAR_CLK_DIV_DEFAULT (1)

View File

@ -0,0 +1,801 @@
// Copyright 2015-2020 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#pragma once
#include <stdbool.h>
#include <stdlib.h>
#include "regi2c_ctrl.h"
#include "esp_attr.h"
#include "soc/adc_periph.h"
#include "hal/adc_types.h"
#include "soc/apb_saradc_struct.h"
#include "soc/apb_saradc_reg.h"
#include "soc/rtc_cntl_struct.h"
#include "soc/rtc_cntl_reg.h"
#ifdef __cplusplus
extern "C" {
#endif
#define ADC_LL_CLKM_DIV_NUM_DEFAULT 15
#define ADC_LL_CLKM_DIV_B_DEFAULT 1
#define ADC_LL_CLKM_DIV_A_DEFAULT 0
typedef enum {
ADC_NUM_1 = 0, /*!< SAR ADC 1 */
ADC_NUM_2 = 1, /*!< SAR ADC 2 */
ADC_NUM_MAX,
} adc_ll_num_t;
typedef enum {
ADC_POWER_BY_FSM, /*!< ADC XPD controled by FSM. Used for polling mode */
ADC_POWER_SW_ON, /*!< ADC XPD controled by SW. power on. Used for DMA mode */
ADC_POWER_SW_OFF, /*!< ADC XPD controled by SW. power off. */
ADC_POWER_MAX, /*!< For parameter check. */
} adc_ll_power_t;
typedef enum {
ADC_RTC_DATA_OK = 0,
ADC_RTC_CTRL_UNSELECTED = 1,
ADC_RTC_CTRL_BREAK = 2,
ADC_RTC_DATA_FAIL = -1,
} adc_ll_rtc_raw_data_t;
//These values should be set according to the HW
typedef enum {
ADC_LL_INTR_THRES1_LOW = BIT(26),
ADC_LL_INTR_THRES0_LOW = BIT(27),
ADC_LL_INTR_THRES1_HIGH = BIT(28),
ADC_LL_INTR_THRES0_HIGH = BIT(29),
ADC_LL_INTR_ADC2_DONE = BIT(30),
ADC_LL_INTR_ADC1_DONE = BIT(31),
} adc_ll_intr_t;
FLAG_ATTR(adc_ll_intr_t)
/**
* @brief ADC controller type selection.
*
* @note For ADC2, use the force option with care. The system power consumption detection will use ADC2.
* If it is forced to switch to another controller, it may cause the system to obtain incorrect values.
* @note Normally, there is no need to switch the controller manually.
*/
typedef enum {
ADC_CTRL_RTC = 0, /*!<For ADC1. Select RTC controller. For ADC2. The controller is selected by the arbiter. Arbiter in default mode. */
ADC_CTRL_DIG = 2, /*!<For ADC1. Select DIG controller. For ADC2. The controller is selected by the arbiter. Arbiter in default mode. */
ADC2_CTRL_PWDET = 3,/*!<For ADC2. The controller is selected by the arbiter. Arbiter in default mode. */
ADC2_CTRL_FORCE_PWDET = 3, /*!<For ADC2. Arbiter in shield mode. Force select Wi-Fi controller work. */
ADC2_CTRL_FORCE_RTC = 4, /*!<For ADC2. Arbiter in shield mode. Force select RTC controller work. */
ADC2_CTRL_FORCE_DIG = 6, /*!<For ADC2. Arbiter in shield mode. Force select digital controller work. */
} adc_ll_controller_t;
/*---------------------------------------------------------------
Digital controller setting
---------------------------------------------------------------*/
/**
* Set adc fsm interval parameter for digital controller. These values are fixed for same platforms.
*
* @param rst_wait cycles between DIG ADC controller reset ADC sensor and start ADC sensor.
* @param start_wait Delay time after open xpd.
* @param standby_wait Delay time to close xpd.
*/
static inline void adc_ll_digi_set_fsm_time(uint32_t rst_wait, uint32_t start_wait, uint32_t standby_wait)
{
// Internal FSM reset wait time
APB_SARADC.fsm_wait.rstb_wait = rst_wait;
// Internal FSM start wait time
APB_SARADC.fsm_wait.xpd_wait = start_wait;
// Internal FSM standby wait time
APB_SARADC.fsm_wait.standby_wait = standby_wait;
}
/**
* Set adc sample cycle for digital controller.
*
* @note Normally, please use default value.
* @param sample_cycle Cycles between DIG ADC controller start ADC sensor and beginning to receive data from sensor.
* Range: 2 ~ 0xFF.
*/
static inline void adc_ll_set_sample_cycle(uint32_t sample_cycle)
{
/* Should be called before writing I2C registers. */
SET_PERI_REG_MASK(RTC_CNTL_ANA_CONF_REG, RTC_CNTL_SAR_I2C_PU);
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SAR1_SAMPLE_CYCLE_ADDR, sample_cycle);
}
/**
* Set SAR ADC module clock division factor.
* SAR ADC clock divided from digital controller clock.
*
* @param div Division factor.
*/
static inline void adc_ll_digi_set_clk_div(uint32_t div)
{
/* ADC clock devided from digital controller clock clk */
APB_SARADC.ctrl.sar_clk_div = div;
}
/**
* Set adc max conversion number for digital controller.
* If the number of ADC conversion is equal to the maximum, the conversion is stopped.
*
* @param meas_num Max conversion number. Range: 0 ~ 255.
*/
static inline void adc_ll_digi_set_convert_limit_num(uint32_t meas_num)
{
APB_SARADC.ctrl2.max_meas_num = meas_num;
}
/**
* Enable max conversion number detection for digital controller.
* If the number of ADC conversion is equal to the maximum, the conversion is stopped.
*/
static inline void adc_ll_digi_convert_limit_enable(void)
{
APB_SARADC.ctrl2.meas_num_limit = 1;
}
/**
* Disable max conversion number detection for digital controller.
* If the number of ADC conversion is equal to the maximum, the conversion is stopped.
*/
static inline void adc_ll_digi_convert_limit_disable(void)
{
APB_SARADC.ctrl2.meas_num_limit = 0;
}
/**
* Set pattern table length for digital controller.
* The pattern table that defines the conversion rules for each SAR ADC. Each table has 8 items, in which channel selection,
* and attenuation are stored. When the conversion is started, the controller reads conversion rules from the
* pattern table one by one. For each controller the scan sequence has at most 8 different rules before repeating itself.
*
* @param adc_n ADC unit.
* @param patt_len Items range: 1 ~ 8.
*/
static inline void adc_ll_digi_set_pattern_table_len(adc_ll_num_t adc_n, uint32_t patt_len)
{
APB_SARADC.ctrl.sar_patt_len = patt_len - 1;
}
/**
* Set pattern table for digital controller.
* The pattern table that defines the conversion rules for each SAR ADC. Each table has 8 items, in which channel selection,
* resolution and attenuation are stored. When the conversion is started, the controller reads conversion rules from the
* pattern table one by one. For each controller the scan sequence has at most 8 different rules before repeating itself.
*
* @param adc_n ADC unit.
* @param pattern_index Items index. Range: 0 ~ 7.
* @param pattern Stored conversion rules.
*/
static inline void adc_ll_digi_set_pattern_table(adc_ll_num_t adc_n, uint32_t pattern_index, adc_digi_pattern_table_t pattern)
{
uint32_t tab;
uint8_t index = pattern_index / 4;
uint8_t offset = (pattern_index % 4) * 6;
tab = APB_SARADC.sar_patt_tab[index].sar_patt_tab1; // Read old register value
tab &= (~(0xFC0000 >> offset)); // Clear old data
tab |= ((uint32_t)(pattern.val & 0x3F) << 18) >> offset; // Fill in the new data
APB_SARADC.sar_patt_tab[index].sar_patt_tab1 = tab; // Write back
}
/**
* Reset the pattern table pointer, then take the measurement rule from table header in next measurement.
*
* @param adc_n ADC unit.
*/
static inline void adc_ll_digi_clear_pattern_table(adc_ll_num_t adc_n)
{
APB_SARADC.ctrl.sar_patt_p_clear = 1;
APB_SARADC.ctrl.sar_patt_p_clear = 0;
}
/**
* Sets the number of cycles required for the conversion to complete and wait for the arbiter to stabilize.
*
* @note Only ADC2 have arbiter function.
* @param cycle range: 0 ~ 4.
*/
static inline void adc_ll_digi_set_arbiter_stable_cycle(uint32_t cycle)
{
APB_SARADC.ctrl.wait_arb_cycle = cycle;
}
/**
* ADC Digital controller output data invert or not.
*
* @param adc_n ADC unit.
* @param inv_en data invert or not.
*/
static inline void adc_ll_digi_output_invert(adc_ll_num_t adc_n, bool inv_en)
{
if (adc_n == ADC_NUM_1) {
APB_SARADC.ctrl2.sar1_inv = inv_en; // Enable / Disable ADC data invert
} else { // adc_n == ADC_NUM_2
APB_SARADC.ctrl2.sar2_inv = inv_en; // Enable / Disable ADC data invert
}
}
/**
* Set the interval clock cycle for the digital controller to trigger the measurement.
* Expression: `trigger_meas_freq` = `controller_clk` / 2 / interval.
*
* @note The trigger interval should not be smaller than the sampling time of the SAR ADC.
* @param cycle The clock cycle (trigger interval) of the measurement. Range: 30 ~ 4095.
*/
static inline void adc_ll_digi_set_trigger_interval(uint32_t cycle)
{
APB_SARADC.ctrl2.timer_target = cycle;
}
/**
* Enable digital controller timer to trigger the measurement.
*/
static inline void adc_ll_digi_trigger_enable(void)
{
APB_SARADC.ctrl2.timer_en = 1;
}
/**
* Disable digital controller timer to trigger the measurement.
*/
static inline void adc_ll_digi_trigger_disable(void)
{
APB_SARADC.ctrl2.timer_en = 0;
}
/**
* Set ADC digital controller clock division factor. The clock divided from `APLL` or `APB` clock.
* Expression: controller_clk = APLL/APB * (div_num + div_b / div_a).
*
* @param div_num Division factor. Range: 1 ~ 255.
* @param div_b Division factor. Range: 1 ~ 63.
* @param div_a Division factor. Range: 0 ~ 63.
*/
static inline void adc_ll_digi_controller_clk_div(uint32_t div_num, uint32_t div_b, uint32_t div_a)
{
APB_SARADC.apb_adc_clkm_conf.clkm_div_num = div_num;
APB_SARADC.apb_adc_clkm_conf.clkm_div_b = div_b;
APB_SARADC.apb_adc_clkm_conf.clkm_div_a = div_a;
}
/**
* Enable clock and select clock source for ADC digital controller.
*
* @param use_apll true: use APLL clock; false: use APB clock.
*/
static inline void adc_ll_digi_controller_clk_enable(bool use_apll)
{
if (use_apll) {
APB_SARADC.apb_adc_clkm_conf.clk_sel = 1; // APLL clock
} else {
APB_SARADC.apb_adc_clkm_conf.clk_sel = 2; // APB clock
}
APB_SARADC.ctrl.sar_clk_gated = 1;
}
/**
* Disable clock for ADC digital controller.
*/
static inline void adc_ll_digi_controller_clk_disable(void)
{
APB_SARADC.ctrl.sar_clk_gated = 0;
}
/**
* Reset adc digital controller filter.
*
* @param adc_n ADC unit.
*/
static inline void adc_ll_digi_filter_reset(adc_ll_num_t adc_n)
{
APB_SARADC.filter_ctrl0.filter_reset = 1;
}
/**
* Set adc digital controller filter factor.
*
* @note If the channel info is not supported, the filter function will not be enabled.
* @param idx ADC filter unit.
* @param filter Filter config. Expression: filter_data = (k-1)/k * last_data + new_data / k. Set values: (2, 4, 8, 16, 64).
*/
static inline void adc_ll_digi_filter_set_factor(adc_digi_filter_idx_t idx, adc_digi_filter_t *filter)
{
if (idx == ADC_DIGI_FILTER_IDX0) {
APB_SARADC.filter_ctrl0.filter_channel0 = (filter->adc_unit << 3) | (filter->channel & 0x7);
APB_SARADC.filter_ctrl1.filter_factor0 = filter->mode;
} else if (idx == ADC_DIGI_FILTER_IDX1) {
APB_SARADC.filter_ctrl0.filter_channel1 = (filter->adc_unit << 3) | (filter->channel & 0x7);
APB_SARADC.filter_ctrl1.filter_factor1 = filter->mode;
}
}
/**
* Get adc digital controller filter factor.
*
* @param adc_n ADC unit.
* @param factor Expression: filter_data = (k-1)/k * last_data + new_data / k. Set values: (2, 4, 8, 16, 64).
*/
static inline void adc_ll_digi_filter_get_factor(adc_digi_filter_idx_t idx, adc_digi_filter_t *filter)
{
if (idx == ADC_DIGI_FILTER_IDX0) {
filter->adc_unit = (APB_SARADC.filter_ctrl0.filter_channel0 >> 3) & 0x1;
filter->channel = APB_SARADC.filter_ctrl0.filter_channel0 & 0x7;
filter->mode = APB_SARADC.filter_ctrl1.filter_factor0;
} else if (idx == ADC_DIGI_FILTER_IDX1) {
filter->adc_unit = (APB_SARADC.filter_ctrl0.filter_channel1 >> 3) & 0x1;
filter->channel = APB_SARADC.filter_ctrl0.filter_channel1 & 0x7;
filter->mode = APB_SARADC.filter_ctrl1.filter_factor1;
}
}
/**
* Disable adc digital controller filter.
* Filtering the ADC data to obtain smooth data at higher sampling rates.
*
* @note If the channel info is not supported, the filter function will not be enabled.
* @param adc_n ADC unit.
*/
static inline void adc_ll_digi_filter_disable(adc_digi_filter_idx_t idx)
{
if (idx == ADC_DIGI_FILTER_IDX0) {
APB_SARADC.filter_ctrl0.filter_channel0 = 0xF;
APB_SARADC.filter_ctrl1.filter_factor0 = 0;
} else if (idx == ADC_DIGI_FILTER_IDX1) {
APB_SARADC.filter_ctrl0.filter_channel1 = 0xF;
APB_SARADC.filter_ctrl1.filter_factor1 = 0;
}
}
/**
* Set monitor mode of adc digital controller.
*
* @note If the channel info is not supported, the monitor function will not be enabled.
* @param adc_n ADC unit.
* @param is_larger true: If ADC_OUT > threshold, Generates monitor interrupt.
* false: If ADC_OUT < threshold, Generates monitor interrupt.
*/
static inline void adc_ll_digi_monitor_set_mode(adc_digi_monitor_idx_t idx, adc_digi_monitor_t *cfg)
{
if (idx == ADC_DIGI_MONITOR_IDX0) {
APB_SARADC.thres0_ctrl.thres0_channel = (cfg->adc_unit << 3) | (cfg->channel & 0x7);
APB_SARADC.thres0_ctrl.thres0_high = cfg->h_threshold;
APB_SARADC.thres0_ctrl.thres0_low = cfg->l_threshold;
} else { // ADC_DIGI_MONITOR_IDX1
APB_SARADC.thres1_ctrl.thres1_channel = (cfg->adc_unit << 3) | (cfg->channel & 0x7);
APB_SARADC.thres1_ctrl.thres1_high = cfg->h_threshold;
APB_SARADC.thres1_ctrl.thres1_low = cfg->l_threshold;
}
}
/**
* Enable/disable monitor of adc digital controller.
*
* @note If the channel info is not supported, the monitor function will not be enabled.
* @param adc_n ADC unit.
*/
static inline void adc_ll_digi_monitor_disable(adc_digi_monitor_idx_t idx)
{
if (idx == ADC_DIGI_MONITOR_IDX0) {
APB_SARADC.thres0_ctrl.thres0_channel = 0xF;
} else { // ADC_DIGI_MONITOR_IDX1
APB_SARADC.thres1_ctrl.thres1_channel = 0xF;
}
}
/**
* Set DMA eof num of adc digital controller.
* If the number of measurements reaches `dma_eof_num`, then `dma_in_suc_eof` signal is generated.
*
* @param num eof num of DMA.
*/
static inline void adc_ll_digi_dma_set_eof_num(uint32_t num)
{
APB_SARADC.dma_conf.apb_adc_eof_num = num;
}
/**
* Enable output data to DMA from adc digital controller.
*/
static inline void adc_ll_digi_dma_enable(void)
{
APB_SARADC.dma_conf.apb_adc_trans = 1;
}
/**
* Disable output data to DMA from adc digital controller.
*/
static inline void adc_ll_digi_dma_disable(void)
{
APB_SARADC.dma_conf.apb_adc_trans = 0;
}
/**
* Reset adc digital controller.
*/
static inline void adc_ll_digi_reset(void)
{
APB_SARADC.dma_conf.apb_adc_reset_fsm = 1;
APB_SARADC.dma_conf.apb_adc_reset_fsm = 0;
}
/*---------------------------------------------------------------
PWDET(Power detect) controller setting
---------------------------------------------------------------*/
/**
* Set adc cct for PWDET controller.
*
* @note Capacitor tuning of the PA power monitor. cct set to the same value with PHY.
* @param cct Range: 0 ~ 7.
*/
static inline void adc_ll_pwdet_set_cct(uint32_t cct)
{
/* Capacitor tuning of the PA power monitor. cct set to the same value with PHY. */
RTCCNTL.sensor_ctrl.sar2_pwdet_cct = cct;
}
/**
* Get adc cct for PWDET controller.
*
* @note Capacitor tuning of the PA power monitor. cct set to the same value with PHY.
* @return cct Range: 0 ~ 7.
*/
static inline uint32_t adc_ll_pwdet_get_cct(void)
{
/* Capacitor tuning of the PA power monitor. cct set to the same value with PHY. */
return RTCCNTL.sensor_ctrl.sar2_pwdet_cct;
}
/**
* Analyze whether the obtained raw data is correct.
* ADC2 can use arbiter. The arbitration result is stored in the channel information of the returned data.
*
* @param adc_n ADC unit.
* @param raw_data ADC raw data input (convert value).
* @return
* - 0: The data is correct to use.
* - -1: The data is invalid.
*/
static inline adc_ll_rtc_raw_data_t adc_ll_analysis_raw_data(adc_ll_num_t adc_n, int raw_data)
{
if (adc_n == ADC_NUM_1) {
return ADC_RTC_DATA_OK;
}
//The raw data API returns value without channel information. Read value directly from the register
if (((APB_SARADC.apb_saradc2_data_status.adc2_data >> 13) & 0xF) > 9) {
return ADC_RTC_DATA_FAIL;
}
return ADC_RTC_DATA_OK;
}
/*---------------------------------------------------------------
Common setting
---------------------------------------------------------------*/
/**
* Set ADC module power management.
*
* @param manage Set ADC power status.
*/
static inline void adc_ll_set_power_manage(adc_ll_power_t manage)
{
// /* Bit1 0:Fsm 1: SW mode
// Bit0 0:SW mode power down 1: SW mode power on */
if (manage == ADC_POWER_SW_ON) {
APB_SARADC.ctrl.sar_clk_gated = 1;
APB_SARADC.ctrl.xpd_sar_force = 3;
} else if (manage == ADC_POWER_BY_FSM) {
APB_SARADC.ctrl.sar_clk_gated = 1;
APB_SARADC.ctrl.xpd_sar_force = 0;
} else if (manage == ADC_POWER_SW_OFF) {
APB_SARADC.ctrl.xpd_sar_force = 2;
APB_SARADC.ctrl.sar_clk_gated = 0;
}
}
/**
* Get ADC module power management.
*
* @return
* - ADC power status.
*/
static inline adc_ll_power_t adc_ll_get_power_manage(void)
{
/* Bit1 0:Fsm 1: SW mode
Bit0 0:SW mode power down 1: SW mode power on */
adc_ll_power_t manage;
if (APB_SARADC.ctrl.xpd_sar_force == 3) {
manage = ADC_POWER_SW_ON;
} else if (APB_SARADC.ctrl.xpd_sar_force == 2) {
manage = ADC_POWER_SW_OFF;
} else {
manage = ADC_POWER_BY_FSM;
}
return manage;
}
/**
* Set ADC2 module arbiter work mode.
* The arbiter is to improve the use efficiency of ADC2. After the control right is robbed by the high priority,
* the low priority controller will read the invalid ADC data, and the validity of the data can be judged by the flag bit in the data.
*
* @note Only ADC2 support arbiter.
* @note The arbiter's working clock is APB_CLK. When the APB_CLK clock drops below 8 MHz, the arbiter must be in shield mode.
*
* @param mode Refer to `adc_arbiter_mode_t`.
*/
static inline void adc_ll_set_arbiter_work_mode(adc_arbiter_mode_t mode)
{
if (mode == ADC_ARB_MODE_FIX) {
APB_SARADC.apb_adc_arb_ctrl.adc_arb_grant_force = 0;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_fix_priority = 1;
} else if (mode == ADC_ARB_MODE_LOOP) {
APB_SARADC.apb_adc_arb_ctrl.adc_arb_grant_force = 0;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_fix_priority = 0;
} else {
APB_SARADC.apb_adc_arb_ctrl.adc_arb_grant_force = 1; // Shield arbiter.
}
}
/**
* Set ADC2 module controller priority in arbiter.
* The arbiter is to improve the use efficiency of ADC2. After the control right is robbed by the high priority,
* the low priority controller will read the invalid ADC data, and the validity of the data can be judged by the flag bit in the data.
*
* @note Only ADC2 support arbiter.
* @note The arbiter's working clock is APB_CLK. When the APB_CLK clock drops below 8 MHz, the arbiter must be in shield mode.
* @note Default priority: Wi-Fi(2) > RTC(1) > Digital(0);
*
* @param pri_rtc RTC controller priority. Range: 0 ~ 2.
* @param pri_dig Digital controller priority. Range: 0 ~ 2.
* @param pri_pwdet Wi-Fi controller priority. Range: 0 ~ 2.
*/
static inline void adc_ll_set_arbiter_priority(uint8_t pri_rtc, uint8_t pri_dig, uint8_t pri_pwdet)
{
if (pri_rtc != pri_dig && pri_rtc != pri_pwdet && pri_dig != pri_pwdet) {
APB_SARADC.apb_adc_arb_ctrl.adc_arb_rtc_priority = pri_rtc;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_apb_priority = pri_dig;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_wifi_priority = pri_pwdet;
}
/* Should select highest priority controller. */
if (pri_rtc > pri_dig) {
if (pri_rtc > pri_pwdet) {
APB_SARADC.apb_adc_arb_ctrl.adc_arb_apb_force = 0;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_rtc_force = 1;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_wifi_force = 0;
} else {
APB_SARADC.apb_adc_arb_ctrl.adc_arb_apb_force = 0;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_rtc_force = 0;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_wifi_force = 1;
}
} else {
if (pri_dig > pri_pwdet) {
APB_SARADC.apb_adc_arb_ctrl.adc_arb_apb_force = 1;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_rtc_force = 0;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_wifi_force = 0;
} else {
APB_SARADC.apb_adc_arb_ctrl.adc_arb_apb_force = 0;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_rtc_force = 0;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_wifi_force = 1;
}
}
}
/* ADC calibration code. */
/**
* @brief Set common calibration configuration. Should be shared with other parts (PWDET).
*/
static inline void adc_ll_calibration_init(adc_ll_num_t adc_n)
{
if (adc_n == ADC_NUM_1) {
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SAR1_DREF_ADDR, 1);
} else {
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SAR2_DREF_ADDR, 1);
}
}
/**
* Configure the registers for ADC calibration. You need to call the ``adc_ll_calibration_finish`` interface to resume after calibration.
*
* @note Different ADC units and different attenuation options use different calibration data (initial data).
*
* @param adc_n ADC index number.
* @param channel adc channel number.
* @param internal_gnd true: Disconnect from the IO port and use the internal GND as the calibration voltage.
* false: Use IO external voltage as calibration voltage.
*/
static inline void adc_ll_calibration_prepare(adc_ll_num_t adc_n, adc_channel_t channel, bool internal_gnd)
{
/* Enable/disable internal connect GND (for calibration). */
if (adc_n == ADC_NUM_1) {
if (internal_gnd) {
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SAR1_ENCAL_GND_ADDR, 1);
} else {
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SAR1_ENCAL_GND_ADDR, 0);
}
} else {
if (internal_gnd) {
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SAR2_ENCAL_GND_ADDR, 1);
} else {
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SAR2_ENCAL_GND_ADDR, 0);
}
}
}
/**
* Resume register status after calibration.
*
* @param adc_n ADC index number.
*/
static inline void adc_ll_calibration_finish(adc_ll_num_t adc_n)
{
if (adc_n == ADC_NUM_1) {
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SAR1_ENCAL_GND_ADDR, 0);
} else {
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SAR2_ENCAL_GND_ADDR, 0);
}
}
/**
* Set the calibration result to ADC.
*
* @note Different ADC units and different attenuation options use different calibration data (initial data).
*
* @param adc_n ADC index number.
*/
static inline void adc_ll_set_calibration_param(adc_ll_num_t adc_n, uint32_t param)
{
uint8_t msb = param >> 8;
uint8_t lsb = param & 0xFF;
if (adc_n == ADC_NUM_1) {
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SAR1_INITIAL_CODE_HIGH_ADDR, msb);
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SAR1_INITIAL_CODE_LOW_ADDR, lsb);
} else {
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SAR2_INITIAL_CODE_HIGH_ADDR, msb);
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SAR2_INITIAL_CODE_LOW_ADDR, lsb);
}
}
/* Temp code end. */
/**
* Output ADCn inter reference voltage to ADC2 channels.
*
* This function routes the internal reference voltage of ADCn to one of
* ADC1's channels. This reference voltage can then be manually measured
* for calibration purposes.
*
* @param[in] adc ADC unit select
* @param[in] channel ADC1 channel number
* @param[in] en Enable/disable the reference voltage output
*/
static inline void adc_ll_vref_output(adc_ll_num_t adc, adc_channel_t channel, bool en)
{
if (en) {
REG_SET_FIELD(RTC_CNTL_SENSOR_CTRL_REG, RTC_CNTL_FORCE_XPD_SAR, 3);
SET_PERI_REG_MASK(RTC_CNTL_REG, RTC_CNTL_REGULATOR_FORCE_PU);
REG_SET_FIELD(APB_SARADC_APB_ADC_CLKM_CONF_REG, APB_SARADC_CLK_SEL, 2);
SET_PERI_REG_MASK(APB_SARADC_APB_ADC_CLKM_CONF_REG, APB_SARADC_CLK_EN);
SET_PERI_REG_MASK(APB_SARADC_APB_ADC_ARB_CTRL_REG, APB_SARADC_ADC_ARB_GRANT_FORCE);
SET_PERI_REG_MASK(APB_SARADC_APB_ADC_ARB_CTRL_REG, APB_SARADC_ADC_ARB_APB_FORCE);
APB_SARADC.sar_patt_tab[0].sar_patt_tab1 = 0xFFFFFF;
APB_SARADC.sar_patt_tab[1].sar_patt_tab1 = 0xFFFFFF;
APB_SARADC.onetime_sample.adc1_onetime_sample = 1;
APB_SARADC.onetime_sample.onetime_channel = channel;
SET_PERI_REG_MASK(RTC_CNTL_ANA_CONF_REG, RTC_CNTL_SAR_I2C_PU);
if (adc == ADC_NUM_1) {
/* Config test mux to route v_ref to ADC1 Channels */
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SARADC1_ENCAL_REF_ADDR, 1);
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SARADC_DTEST_RTC_ADDR, 1);
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SARADC_ENT_TSENS_ADDR, 0);
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SARADC_ENT_RTC_ADDR, 1);
} else {
/* Config test mux to route v_ref to ADC2 Channels */
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SARADC2_ENCAL_REF_ADDR, 1);
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SARADC_DTEST_RTC_ADDR, 0);
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SARADC_ENT_TSENS_ADDR, 0);
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SARADC_ENT_RTC_ADDR, 0);
}
} else {
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SARADC2_ENCAL_REF_ADDR, 0);
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SARADC1_ENCAL_REF_ADDR, 0);
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SARADC_DTEST_RTC_ADDR, 0);
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SARADC_ENT_RTC_ADDR, 0);
APB_SARADC.onetime_sample.adc1_onetime_sample = 0;
APB_SARADC.onetime_sample.onetime_channel = 0xf;
REG_SET_FIELD(RTC_CNTL_SENSOR_CTRL_REG, RTC_CNTL_FORCE_XPD_SAR, 0);
REG_SET_FIELD(APB_SARADC_APB_ADC_CLKM_CONF_REG, APB_SARADC_CLK_SEL, 0);
CLEAR_PERI_REG_MASK(APB_SARADC_APB_ADC_CLKM_CONF_REG, APB_SARADC_CLK_EN);
CLEAR_PERI_REG_MASK(APB_SARADC_APB_ADC_ARB_CTRL_REG, APB_SARADC_ADC_ARB_GRANT_FORCE);
CLEAR_PERI_REG_MASK(APB_SARADC_APB_ADC_ARB_CTRL_REG, APB_SARADC_ADC_ARB_APB_FORCE);
}
}
/*---------------------------------------------------------------
Single Read
---------------------------------------------------------------*/
/**
* Trigger single read
*
* @param val Usage: set to 1 to start the ADC conversion. The step signal should at least keep 3 ADC digital controller clock cycle,
* otherwise the step signal may not be captured by the ADC digital controller when its frequency is slow.
* This hardware limitation will be removed in future versions.
*/
static inline void adc_ll_onetime_start(bool val)
{
APB_SARADC.onetime_sample.onetime_start = val;
}
static inline void adc_ll_onetime_set_channel(adc_ll_num_t unit, adc_channel_t channel)
{
APB_SARADC.onetime_sample.onetime_channel = ((unit << 3) | channel);
}
static inline void adc_ll_onetime_set_atten(adc_atten_t atten)
{
APB_SARADC.onetime_sample.onetime_atten = atten;
}
static inline void adc_ll_intr_enable(adc_ll_intr_t mask)
{
APB_SARADC.int_ena.val |= mask;
}
static inline void adc_ll_intr_disable(adc_ll_intr_t mask)
{
APB_SARADC.int_ena.val &= ~mask;
}
static inline void adc_ll_intr_clear(adc_ll_intr_t mask)
{
APB_SARADC.int_clr.val |= mask;
}
static inline bool adc_ll_intr_get_raw(adc_ll_intr_t mask)
{
return (APB_SARADC.int_raw.val & mask);
}
static inline bool adc_ll_intr_get_status(adc_ll_intr_t mask)
{
return (APB_SARADC.int_st.val & mask);
}
static inline void adc_ll_onetime_sample_enable(adc_ll_num_t adc_n, bool enable)
{
if (adc_n == ADC_NUM_1) {
APB_SARADC.onetime_sample.adc1_onetime_sample = enable;
} else {
APB_SARADC.onetime_sample.adc2_onetime_sample = enable;
}
}
static inline uint32_t adc_ll_adc1_read(void)
{
//On ESP32C3, valid data width is 12-bit
return (APB_SARADC.apb_saradc1_data_status.adc1_data & 0xfff);
}
static inline uint32_t adc_ll_adc2_read(void)
{
//On ESP32C3, valid data width is 12-bit
return (APB_SARADC.apb_saradc2_data_status.adc2_data & 0xfff);
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,235 @@
// 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 <stdbool.h>
#include "soc/hwcrypto_reg.h"
#include "hal/aes_types.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief State of AES accelerator, busy, idle or done
*
*/
typedef enum {
ESP_AES_STATE_IDLE = 0, /* AES accelerator is idle */
ESP_AES_STATE_BUSY, /* Transform in progress */
ESP_AES_STATE_DONE, /* Transform completed */
} esp_aes_state_t;
/**
* @brief Write the encryption/decryption key to hardware
*
* @param key Key to be written to the AES hardware
* @param key_word_len Number of words in the key
*
* @return volatile number of bytes written to hardware, used for fault injection check
*/
static inline uint8_t aes_ll_write_key(const uint8_t *key, size_t key_word_len)
{
/* This variable is used for fault injection checks, so marked volatile to avoid optimisation */
volatile uint8_t key_in_hardware = 0;
uint32_t *key_words = (uint32_t *)key;
for (int i = 0; i < key_word_len; i++) {
REG_WRITE(AES_KEY_BASE + i * 4, *(key_words + i));
key_in_hardware += 4;
}
return key_in_hardware;
}
/**
* @brief Sets the mode
*
* @param mode ESP_AES_ENCRYPT = 1, or ESP_AES_DECRYPT = 0
* @param key_bytes Number of bytes in the key
*/
static inline void aes_ll_set_mode(int mode, uint8_t key_bytes)
{
const uint32_t MODE_DECRYPT_BIT = 4;
unsigned mode_reg_base = (mode == ESP_AES_ENCRYPT) ? 0 : MODE_DECRYPT_BIT;
/* See TRM for the mapping between keylength and mode bit */
REG_WRITE(AES_MODE_REG, mode_reg_base + ((key_bytes / 8) - 2));
}
/**
* @brief Writes message block to AES hardware
*
* @param input Block to be written
*/
static inline void aes_ll_write_block(const void *input)
{
const uint32_t *input_words = (const uint32_t *)input;
uint32_t i0, i1, i2, i3;
/* Storing i0,i1,i2,i3 in registers, not in an array
helps a lot with optimisations at -Os level */
i0 = input_words[0];
REG_WRITE(AES_TEXT_IN_BASE, i0);
i1 = input_words[1];
REG_WRITE(AES_TEXT_IN_BASE + 4, i1);
i2 = input_words[2];
REG_WRITE(AES_TEXT_IN_BASE + 8, i2);
i3 = input_words[3];
REG_WRITE(AES_TEXT_IN_BASE + 12, i3);
}
/**
* @brief Read the AES block
*
* @param output the output of the transform, length = AES_BLOCK_BYTES
*/
static inline void aes_ll_read_block(void *output)
{
uint32_t *output_words = (uint32_t *)output;
const size_t REG_WIDTH = sizeof(uint32_t);
for (size_t i = 0; i < AES_BLOCK_WORDS; i++) {
output_words[i] = REG_READ(AES_TEXT_OUT_BASE + (i * REG_WIDTH));
}
}
/**
* @brief Starts block transform
*
*/
static inline void aes_ll_start_transform(void)
{
REG_WRITE(AES_TRIGGER_REG, 1);
}
/**
* @brief Read state of AES accelerator
*
* @return esp_aes_state_t
*/
static inline esp_aes_state_t aes_ll_get_state(void)
{
return REG_READ(AES_STATE_REG);
}
/**
* @brief Set mode of operation
*
* @note Only used for DMA transforms
*
* @param mode
*/
static inline void aes_ll_set_block_mode(esp_aes_mode_t mode)
{
REG_WRITE(AES_BLOCK_MODE_REG, mode);
}
/**
* @brief Set AES-CTR counter to INC32
*
* @note Only affects AES-CTR mode
*
*/
static inline void aes_ll_set_inc(void)
{
REG_WRITE(AES_INC_SEL_REG, 0);
}
/**
* @brief Release the DMA
*
*/
static inline void aes_ll_dma_exit(void)
{
REG_WRITE(AES_DMA_EXIT_REG, 0);
}
/**
* @brief Sets the number of blocks to be transformed
*
* @note Only used for DMA transforms
*
* @param num_blocks Number of blocks to transform
*/
static inline void aes_ll_set_num_blocks(size_t num_blocks)
{
REG_WRITE(AES_BLOCK_NUM_REG, num_blocks);
}
/*
* Write IV to hardware iv registers
*/
static inline void aes_ll_set_iv(const uint8_t *iv)
{
uint32_t *iv_words = (uint32_t *)iv;
uint32_t *reg_addr_buf = (uint32_t *)(AES_IV_BASE);
for (int i = 0; i < IV_WORDS; i++ ) {
REG_WRITE(&reg_addr_buf[i], iv_words[i]);
}
}
/*
* Read IV from hardware iv registers
*/
static inline void aes_ll_read_iv(uint8_t *iv)
{
uint32_t *iv_words = (uint32_t *)iv;
const size_t REG_WIDTH = sizeof(uint32_t);
for (size_t i = 0; i < IV_WORDS; i++) {
iv_words[i] = REG_READ(AES_IV_BASE + (i * REG_WIDTH));
}
}
/**
* @brief Enable or disable DMA mode
*
* @param enable true to enable, false to disable.
*/
static inline void aes_ll_dma_enable(bool enable)
{
REG_WRITE(AES_DMA_ENABLE_REG, enable);
}
/**
* @brief Enable or disable transform completed interrupt
*
* @param enable true to enable, false to disable.
*/
static inline void aes_ll_interrupt_enable(bool enable)
{
REG_WRITE(AES_INT_ENA_REG, enable);
}
/**
* @brief Clears the interrupt
*
*/
static inline void aes_ll_interrupt_clear(void)
{
REG_WRITE(AES_INT_CLR_REG, 1);
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,252 @@
// 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/periph_defs.h"
#include "soc/system_reg.h"
#include "soc/syscon_reg.h"
#include "soc/dport_access.h"
static inline uint32_t periph_ll_get_clk_en_mask(periph_module_t periph)
{
switch (periph) {
case PERIPH_SARADC_MODULE:
return SYSTEM_APB_SARADC_CLK_EN;
case PERIPH_RMT_MODULE:
return SYSTEM_RMT_CLK_EN;
case PERIPH_LEDC_MODULE:
return SYSTEM_LEDC_CLK_EN;
case PERIPH_UART0_MODULE:
return SYSTEM_UART_CLK_EN;
case PERIPH_UART1_MODULE:
return SYSTEM_UART1_CLK_EN;
case PERIPH_I2C0_MODULE:
return SYSTEM_I2C_EXT0_CLK_EN;
case PERIPH_I2S1_MODULE:
return SYSTEM_I2S1_CLK_EN;
case PERIPH_TIMG0_MODULE:
return SYSTEM_TIMERGROUP_CLK_EN;
case PERIPH_TIMG1_MODULE:
return SYSTEM_TIMERGROUP1_CLK_EN;
case PERIPH_UHCI0_MODULE:
return SYSTEM_UHCI0_CLK_EN;
case PERIPH_SYSTIMER_MODULE:
return SYSTEM_SYSTIMER_CLK_EN;
case PERIPH_SPI_MODULE:
return SYSTEM_SPI01_CLK_EN;
case PERIPH_SPI2_MODULE:
return SYSTEM_SPI2_CLK_EN;
case PERIPH_TWAI_MODULE:
return SYSTEM_TWAI_CLK_EN;
case PERIPH_GDMA_MODULE:
return SYSTEM_DMA_CLK_EN;
case PERIPH_AES_MODULE:
return SYSTEM_CRYPTO_AES_CLK_EN;
case PERIPH_SHA_MODULE:
return SYSTEM_CRYPTO_SHA_CLK_EN;
case PERIPH_RSA_MODULE:
return SYSTEM_CRYPTO_RSA_CLK_EN;
case PERIPH_HMAC_MODULE:
return SYSTEM_CRYPTO_HMAC_CLK_EN;
case PERIPH_DS_MODULE:
return SYSTEM_CRYPTO_DS_CLK_EN;
case PERIPH_RNG_MODULE:
return SYSTEM_WIFI_CLK_RNG_EN;
case PERIPH_WIFI_MODULE:
return SYSTEM_WIFI_CLK_WIFI_EN_M;
case PERIPH_BT_MODULE:
return SYSTEM_WIFI_CLK_BT_EN_M;
case PERIPH_WIFI_BT_COMMON_MODULE:
return SYSTEM_WIFI_CLK_WIFI_BT_COMMON_M;
case PERIPH_BT_BASEBAND_MODULE:
return SYSTEM_BT_BASEBAND_EN;
case PERIPH_BT_LC_MODULE:
return SYSTEM_BT_LC_EN;
default:
return 0;
}
}
static inline uint32_t periph_ll_get_rst_en_mask(periph_module_t periph, bool enable)
{
(void)enable; // unused
switch (periph) {
case PERIPH_SARADC_MODULE:
return SYSTEM_APB_SARADC_RST;
case PERIPH_RMT_MODULE:
return SYSTEM_RMT_RST;
case PERIPH_LEDC_MODULE:
return SYSTEM_LEDC_RST;
case PERIPH_UART0_MODULE:
return SYSTEM_UART_RST;
case PERIPH_UART1_MODULE:
return SYSTEM_UART1_RST;
case PERIPH_I2C0_MODULE:
return SYSTEM_I2C_EXT0_RST;
case PERIPH_I2S1_MODULE:
return SYSTEM_I2S1_RST;
case PERIPH_TIMG0_MODULE:
return SYSTEM_TIMERGROUP_RST;
case PERIPH_TIMG1_MODULE:
return SYSTEM_TIMERGROUP1_RST;
case PERIPH_UHCI0_MODULE:
return SYSTEM_UHCI0_RST;
case PERIPH_SYSTIMER_MODULE:
return SYSTEM_SYSTIMER_RST;
case PERIPH_GDMA_MODULE:
return SYSTEM_DMA_RST;
case PERIPH_SPI_MODULE:
return SYSTEM_SPI01_RST;
case PERIPH_SPI2_MODULE:
return SYSTEM_SPI2_RST;
case PERIPH_TWAI_MODULE:
return SYSTEM_TWAI_RST;
case PERIPH_HMAC_MODULE:
return SYSTEM_CRYPTO_HMAC_RST;
case PERIPH_AES_MODULE:
if (enable == true) {
// Clear reset on digital signature, otherwise AES unit is held in reset also.
return (SYSTEM_CRYPTO_AES_RST | SYSTEM_CRYPTO_DS_RST);
} else {
//Don't return other units to reset, as this pulls reset on RSA & SHA units, respectively.
return SYSTEM_CRYPTO_AES_RST;
}
case PERIPH_SHA_MODULE:
if (enable == true) {
// Clear reset on digital signature and HMAC, otherwise SHA is held in reset
return (SYSTEM_CRYPTO_SHA_RST | SYSTEM_CRYPTO_DS_RST | SYSTEM_CRYPTO_HMAC_RST);
} else {
// Don't assert reset on secure boot, otherwise AES is held in reset
return SYSTEM_CRYPTO_SHA_RST;
}
case PERIPH_RSA_MODULE:
if (enable == true) {
/* also clear reset on digital signature, otherwise RSA is held in reset */
return (SYSTEM_CRYPTO_RSA_RST | SYSTEM_CRYPTO_DS_RST);
} else {
/* don't reset digital signature unit, as this resets AES also */
return SYSTEM_CRYPTO_RSA_RST;
}
case PERIPH_DS_MODULE:
return SYSTEM_CRYPTO_DS_RST;
default:
return 0;
}
}
static uint32_t periph_ll_get_clk_en_reg(periph_module_t periph)
{
switch (periph) {
case PERIPH_RNG_MODULE:
case PERIPH_WIFI_MODULE:
case PERIPH_BT_MODULE:
case PERIPH_WIFI_BT_COMMON_MODULE:
case PERIPH_BT_BASEBAND_MODULE:
case PERIPH_BT_LC_MODULE:
return SYSTEM_WIFI_CLK_EN_REG;
case PERIPH_HMAC_MODULE:
case PERIPH_DS_MODULE:
case PERIPH_AES_MODULE:
case PERIPH_RSA_MODULE:
case PERIPH_SHA_MODULE:
case PERIPH_GDMA_MODULE:
return SYSTEM_PERIP_CLK_EN1_REG;
default:
return SYSTEM_PERIP_CLK_EN0_REG;
}
}
static uint32_t periph_ll_get_rst_en_reg(periph_module_t periph)
{
switch (periph) {
case PERIPH_RNG_MODULE:
case PERIPH_WIFI_MODULE:
case PERIPH_BT_MODULE:
case PERIPH_WIFI_BT_COMMON_MODULE:
case PERIPH_BT_BASEBAND_MODULE:
case PERIPH_BT_LC_MODULE:
return SYSTEM_WIFI_RST_EN_REG;
case PERIPH_HMAC_MODULE:
case PERIPH_DS_MODULE:
case PERIPH_AES_MODULE:
case PERIPH_RSA_MODULE:
case PERIPH_SHA_MODULE:
case PERIPH_GDMA_MODULE:
return SYSTEM_PERIP_RST_EN1_REG;
default:
return SYSTEM_PERIP_RST_EN0_REG;
}
}
static inline void periph_ll_enable_clk_clear_rst(periph_module_t periph)
{
DPORT_SET_PERI_REG_MASK(periph_ll_get_clk_en_reg(periph), periph_ll_get_clk_en_mask(periph));
DPORT_CLEAR_PERI_REG_MASK(periph_ll_get_rst_en_reg(periph), periph_ll_get_rst_en_mask(periph, true));
}
static inline void periph_ll_disable_clk_set_rst(periph_module_t periph)
{
DPORT_CLEAR_PERI_REG_MASK(periph_ll_get_clk_en_reg(periph), periph_ll_get_clk_en_mask(periph));
DPORT_SET_PERI_REG_MASK(periph_ll_get_rst_en_reg(periph), periph_ll_get_rst_en_mask(periph, false));
}
static inline void IRAM_ATTR periph_ll_wifi_bt_module_enable_clk_clear_rst(void)
{
DPORT_SET_PERI_REG_MASK(SYSTEM_WIFI_CLK_EN_REG, SYSTEM_WIFI_CLK_WIFI_BT_COMMON_M);
DPORT_CLEAR_PERI_REG_MASK(SYSTEM_CORE_RST_EN_REG, 0);
}
static inline void IRAM_ATTR periph_ll_wifi_bt_module_disable_clk_set_rst(void)
{
DPORT_CLEAR_PERI_REG_MASK(SYSTEM_WIFI_CLK_EN_REG, SYSTEM_WIFI_CLK_WIFI_BT_COMMON_M);
DPORT_SET_PERI_REG_MASK(SYSTEM_CORE_RST_EN_REG, 0);
}
static inline void periph_ll_reset(periph_module_t periph)
{
DPORT_SET_PERI_REG_MASK(periph_ll_get_rst_en_reg(periph), periph_ll_get_rst_en_mask(periph, false));
DPORT_CLEAR_PERI_REG_MASK(periph_ll_get_rst_en_reg(periph), periph_ll_get_rst_en_mask(periph, false));
}
static inline bool IRAM_ATTR periph_ll_periph_enabled(periph_module_t periph)
{
return DPORT_REG_GET_BIT(periph_ll_get_rst_en_reg(periph), periph_ll_get_rst_en_mask(periph, false)) == 0 &&
DPORT_REG_GET_BIT(periph_ll_get_clk_en_reg(periph), periph_ll_get_clk_en_mask(periph)) != 0;
}
static inline void periph_ll_wifi_module_enable_clk_clear_rst(void)
{
DPORT_SET_PERI_REG_MASK(SYSTEM_WIFI_CLK_EN_REG, SYSTEM_WIFI_CLK_WIFI_EN_M);
DPORT_CLEAR_PERI_REG_MASK(SYSTEM_CORE_RST_EN_REG, 0);
}
static inline void periph_ll_wifi_module_disable_clk_set_rst(void)
{
DPORT_CLEAR_PERI_REG_MASK(SYSTEM_WIFI_CLK_EN_REG, SYSTEM_WIFI_CLK_WIFI_EN_M);
DPORT_SET_PERI_REG_MASK(SYSTEM_CORE_RST_EN_REG, 0);
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,161 @@
// 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_caps.h"
#include "esp_bit_defs.h"
#include "soc/assist_debug_reg.h"
#include "esp_attr.h"
#include "riscv/csr.h"
/*performance counter*/
#define CSR_PCER_MACHINE 0x7e0
#define CSR_PCMR_MACHINE 0x7e1
#define CSR_PCCR_MACHINE 0x7e2
#ifdef __cplusplus
extern "C" {
#endif
static inline int IRAM_ATTR cpu_ll_get_core_id(void)
{
#if SOC_CPU_CORES_NUM == 1
return 0; // No need to check core ID on single core hardware
#else
int cpuid;
cpuid = RV_READ_CSR(mhartid);
return cpuid;
#endif
}
static inline void cpu_ll_enable_cycle_count(void)
{
RV_WRITE_CSR(CSR_PCER_MACHINE,1);
RV_WRITE_CSR(CSR_PCMR_MACHINE,1);
return;
}
static inline uint32_t IRAM_ATTR cpu_ll_get_cycle_count(void)
{
uint32_t result;
result = RV_READ_CSR(CSR_PCCR_MACHINE);
return result;
}
static inline void IRAM_ATTR cpu_ll_set_cycle_count(uint32_t val)
{
RV_WRITE_CSR(CSR_PCCR_MACHINE, val);
}
static inline void* cpu_ll_get_sp(void)
{
void *sp;
asm volatile ("mv %0, sp;" : "=r" (sp));
return sp;
}
static inline void cpu_ll_init_hwloop(void)
{
// Nothing needed here for ESP32-C3
}
static inline void cpu_ll_set_breakpoint(int id, uint32_t pc)
{
RV_WRITE_CSR(tselect,id);
RV_SET_CSR(CSR_TCONTROL,TCONTROL_MTE);
RV_SET_CSR(CSR_TDATA1, TDATA1_USER|TDATA1_MACHINE|TDATA1_EXECUTE);
RV_WRITE_CSR(tdata2,pc);
return;
}
static inline void cpu_ll_clear_breakpoint(int id)
{
RV_WRITE_CSR(tselect,id);
RV_CLEAR_CSR(CSR_TCONTROL,TCONTROL_MTE);
RV_CLEAR_CSR(CSR_TDATA1, TDATA1_USER|TDATA1_MACHINE|TDATA1_EXECUTE);
return;
}
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)
{
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)
{
uint32_t addr_napot;
RV_WRITE_CSR(tselect,id);
RV_SET_CSR(CSR_TCONTROL, TCONTROL_MPTE | TCONTROL_MTE);
RV_SET_CSR(CSR_TDATA1, TDATA1_USER|TDATA1_MACHINE);
RV_SET_CSR_FIELD(CSR_TDATA1, TDATA1_MATCH, 1);
// add 0 in napot encoding
addr_napot = ((uint32_t) addr) | ((size >> 1) - 1);
if (on_read) {
RV_SET_CSR(CSR_TDATA1, TDATA1_LOAD);
}
if (on_write) {
RV_SET_CSR(CSR_TDATA1, TDATA1_STORE);
}
RV_WRITE_CSR(tdata2,addr_napot);
return;
}
static inline void cpu_ll_clear_watchpoint(int id)
{
RV_WRITE_CSR(tselect,id);
RV_CLEAR_CSR(CSR_TCONTROL,TCONTROL_MTE);
RV_CLEAR_CSR(CSR_TDATA1, TDATA1_USER|TDATA1_MACHINE);
RV_CLEAR_CSR_FIELD(CSR_TDATA1,TDATA1_MATCH);
RV_CLEAR_CSR(CSR_TDATA1, TDATA1_MACHINE);
RV_CLEAR_CSR(CSR_TDATA1, TDATA1_LOAD|TDATA1_STORE|TDATA1_EXECUTE);
return;
}
FORCE_INLINE_ATTR bool cpu_ll_is_debugger_attached(void)
{
return REG_GET_BIT(ASSIST_DEBUG_C0RE_0_DEBUG_MODE_REG, ASSIST_DEBUG_CORE_0_DEBUG_MODULE_ACTIVE);
}
static inline void cpu_ll_break(void)
{
asm volatile("ebreak\n");
return;
}
static inline void cpu_ll_set_vecbase(const void* vecbase)
{
uintptr_t vecbase_int = (uintptr_t)vecbase;
vecbase_int |= 1; // Set MODE field to treat MTVEC as a vector base address
RV_WRITE_CSR(mtvec, vecbase_int);
}
static inline void cpu_ll_waiti(void)
{
asm volatile ("wfi\n");
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,175 @@
// 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.
/*******************************************************************************
* NOTICE
* The hal is not public api, don't use it in application code.
******************************************************************************/
#pragma once
#include <stdint.h>
#include <stdbool.h>
#include <string.h>
#include "soc/hwcrypto_reg.h"
#include "soc/soc_caps.h"
#ifdef __cplusplus
extern "C" {
#endif
static inline void ds_ll_start(void)
{
REG_WRITE(DS_SET_START_REG, 1);
}
/**
* @brief Wait until DS peripheral has finished any outstanding operation.
*/
static inline bool ds_ll_busy(void)
{
return (REG_READ(DS_QUERY_BUSY_REG) > 0) ? true : false;
}
/**
* @brief Busy wait until the hardware is ready.
*/
static inline void ds_ll_wait_busy(void)
{
while (ds_ll_busy());
}
/**
* @brief In case of a key error, check what caused it.
*/
static inline ds_key_check_t ds_ll_key_error_source(void)
{
uint32_t key_error = REG_READ(DS_QUERY_KEY_WRONG_REG);
if (key_error == 0) {
return DS_NO_KEY_INPUT;
} else {
return DS_OTHER_WRONG;
}
}
/**
* @brief Write the initialization vector to the corresponding register field.
*/
static inline void ds_ll_configure_iv(const uint32_t *iv)
{
for (size_t i = 0; i < (SOC_DS_KEY_PARAM_MD_IV_LENGTH / sizeof(uint32_t)); i++) {
REG_WRITE(DS_IV_BASE + (i * 4) , iv[i]);
}
}
/**
* @brief Write the message which should be signed.
*
* @param msg Pointer to the message.
* @param size Length of msg in bytes. It is the RSA signature length in bytes.
*/
static inline void ds_ll_write_message(const uint8_t *msg, size_t size)
{
memcpy((uint8_t*) DS_X_BASE, msg, size);
asm volatile ("fence");
}
/**
* @brief Write the encrypted private key parameters.
*/
static inline void ds_ll_write_private_key_params(const uint8_t *encrypted_key_params)
{
/* Note: as the internal peripheral still has RSA 4096 structure,
but C is encrypted based on the actual max RSA length (ETS_DS_MAX_BITS), need to fragment it
when copying to hardware...
(note if ETS_DS_MAX_BITS == 4096, this should be the same as copying data->c to hardware in one fragment)
*/
typedef struct { uint32_t addr; size_t len; } frag_t;
const frag_t frags[] = {
{DS_C_Y_BASE, SOC_DS_SIGNATURE_MAX_BIT_LEN / 8},
{DS_C_M_BASE, SOC_DS_SIGNATURE_MAX_BIT_LEN / 8},
{DS_C_RB_BASE, SOC_DS_SIGNATURE_MAX_BIT_LEN / 8},
{DS_C_BOX_BASE, DS_IV_BASE - DS_C_BOX_BASE},
};
const size_t NUM_FRAGS = sizeof(frags)/sizeof(frag_t);
const uint8_t *from = encrypted_key_params;
for (int i = 0; i < NUM_FRAGS; i++) {
memcpy((uint8_t *)frags[i].addr, from, frags[i].len);
asm volatile ("fence");
from += frags[i].len;
}
}
/**
* @brief Begin signing procedure.
*/
static inline void ds_ll_start_sign(void)
{
REG_WRITE(DS_SET_ME_REG, 1);
}
/**
* @brief check the calculated signature.
*
* @return
* - DS_SIGNATURE_OK if no issue is detected with the signature.
* - DS_SIGNATURE_PADDING_FAIL if the padding of the private key parameters is wrong.
* - DS_SIGNATURE_MD_FAIL if the message digest check failed. This means that the message digest calculated using
* the private key parameters fails, i.e., the integrity of the private key parameters is not protected.
* - DS_SIGNATURE_PADDING_AND_MD_FAIL if both padding and message digest check fail.
*/
static inline ds_signature_check_t ds_ll_check_signature(void)
{
uint32_t result = REG_READ(DS_QUERY_CHECK_REG);
switch(result) {
case 0:
return DS_SIGNATURE_OK;
case 1:
return DS_SIGNATURE_MD_FAIL;
case 2:
return DS_SIGNATURE_PADDING_FAIL;
default:
return DS_SIGNATURE_PADDING_AND_MD_FAIL;
}
}
/**
* @brief Read the signature from the hardware.
*
* @param result The signature result.
* @param size Length of signature result in bytes. It is the RSA signature length in bytes.
*/
static inline void ds_ll_read_result(uint8_t *result, size_t size)
{
memcpy(result, (uint8_t*) DS_Z_BASE, size);
asm volatile ("fence");
}
/**
* @brief Exit the signature operation.
*
* @note This does not deactivate the module. Corresponding clock/reset bits have to be triggered for deactivation.
*/
static inline void ds_ll_finish(void)
{
REG_WRITE(DS_SET_FINISH_REG, 1);
ds_ll_wait_busy();
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,456 @@
// 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 "soc/gdma_struct.h"
#include "soc/gdma_reg.h"
#ifdef __cplusplus
extern "C" {
#endif
#define GDMA_LL_GET_HW(id) (((id) == 0) ? (&GDMA) : NULL)
#define GDMA_LL_RX_EVENT_MASK (0x06A7)
#define GDMA_LL_TX_EVENT_MASK (0x1958)
#define GDMA_LL_EVENT_TX_FIFO_UDF (1<<12)
#define GDMA_LL_EVENT_TX_FIFO_OVF (1<<11)
#define GDMA_LL_EVENT_RX_FIFO_UDF (1<<10)
#define GDMA_LL_EVENT_RX_FIFO_OVF (1<<9)
#define GDMA_LL_EVENT_TX_TOTAL_EOF (1<<8)
#define GDMA_LL_EVENT_RX_DESC_EMPTY (1<<7)
#define GDMA_LL_EVENT_TX_DESC_ERROR (1<<6)
#define GDMA_LL_EVENT_RX_DESC_ERROR (1<<5)
#define GDMA_LL_EVENT_TX_EOF (1<<4)
#define GDMA_LL_EVENT_TX_DONE (1<<3)
#define GDMA_LL_EVENT_RX_ERR_EOF (1<<2)
#define GDMA_LL_EVENT_RX_SUC_EOF (1<<1)
#define GDMA_LL_EVENT_RX_DONE (1<<0)
///////////////////////////////////// Common /////////////////////////////////////////
/**
* @brief Enable DMA channel M2M mode (TX channel n forward data to RX channel n), disabled by default
*/
static inline void gdma_ll_enable_m2m_mode(gdma_dev_t *dev, uint32_t channel, bool enable)
{
dev->channel[channel].in.in_conf0.mem_trans_en = enable;
if (enable) {
// to enable m2m mode, the tx chan has to be the same to rx chan, and set to a valid value
dev->channel[channel].in.in_peri_sel.sel = 0;
dev->channel[channel].out.out_peri_sel.sel = 0;
}
}
/**
* @brief Enable DMA clock gating
*/
static inline void gdma_ll_enable_clock(gdma_dev_t *dev, bool enable)
{
dev->misc_conf.clk_en = enable;
}
///////////////////////////////////// RX /////////////////////////////////////////
/**
* @brief Get DMA RX channel interrupt status word
*/
static inline uint32_t gdma_ll_rx_get_interrupt_status(gdma_dev_t *dev, uint32_t channel)
{
return dev->intr[channel].st.val & GDMA_LL_RX_EVENT_MASK;
}
/**
* @brief Enable DMA RX channel interrupt
*/
static inline void gdma_ll_rx_enable_interrupt(gdma_dev_t *dev, uint32_t channel, uint32_t mask, bool enable)
{
if (enable) {
dev->intr[channel].ena.val |= (mask & GDMA_LL_RX_EVENT_MASK);
} else {
dev->intr[channel].ena.val &= ~(mask & GDMA_LL_RX_EVENT_MASK);
}
}
/**
* @brief Clear DMA RX channel interrupt
*/
static inline void gdma_ll_rx_clear_interrupt_status(gdma_dev_t *dev, uint32_t channel, uint32_t mask)
{
dev->intr[channel].clr.val = (mask & GDMA_LL_RX_EVENT_MASK);
}
/**
* @brief Get DMA RX channel interrupt status register address
*/
static inline volatile void *gdma_ll_rx_get_interrupt_status_reg(gdma_dev_t *dev, uint32_t channel)
{
return (volatile void *)(&dev->intr[channel].st);
}
/**
* @brief Enable DMA RX channel to check the owner bit in the descriptor, disabled by default
*/
static inline void gdma_ll_rx_enable_owner_check(gdma_dev_t *dev, uint32_t channel, bool enable)
{
dev->channel[channel].in.in_conf1.in_check_owner = enable;
}
/**
* @brief Enable DMA RX channel burst reading data, disabled by default
*/
static inline void gdma_ll_rx_enable_data_burst(gdma_dev_t *dev, uint32_t channel, bool enable)
{
dev->channel[channel].in.in_conf0.in_data_burst_en = enable;
}
/**
* @brief Enable DMA RX channel burst reading descriptor link, disabled by default
*/
static inline void gdma_ll_rx_enable_descriptor_burst(gdma_dev_t *dev, uint32_t channel, bool enable)
{
dev->channel[channel].in.in_conf0.indscr_burst_en = enable;
}
/**
* @brief Reset DMA RX channel FSM and FIFO pointer
*/
static inline void gdma_ll_rx_reset_channel(gdma_dev_t *dev, uint32_t channel)
{
dev->channel[channel].in.in_conf0.in_rst = 1;
dev->channel[channel].in.in_conf0.in_rst = 0;
}
/**
* @brief Check if DMA RX FIFO is full
* @param fifo_level only supports level 1
*/
static inline bool gdma_ll_rx_is_fifo_full(gdma_dev_t *dev, uint32_t channel, uint32_t fifo_level)
{
return dev->channel[channel].in.infifo_status.val & 0x01;
}
/**
* @brief Check if DMA RX FIFO is empty
* @param fifo_level only supports level 1
*/
static inline bool gdma_ll_rx_is_fifo_empty(gdma_dev_t *dev, uint32_t channel, uint32_t fifo_level)
{
return dev->channel[channel].in.infifo_status.val & 0x02;
}
/**
* @brief Get number of bytes in RX FIFO
* @param fifo_level only supports level 1
*/
static inline uint32_t gdma_ll_rx_get_fifo_bytes(gdma_dev_t *dev, uint32_t channel, uint32_t fifo_level)
{
return dev->channel[channel].in.infifo_status.infifo_cnt;
}
/**
* @brief Pop data from DMA RX FIFO
*/
static inline uint32_t gdma_ll_rx_pop_data(gdma_dev_t *dev, uint32_t channel)
{
dev->channel[channel].in.in_pop.infifo_pop = 1;
return dev->channel[channel].in.in_pop.infifo_rdata;
}
/**
* @brief Set the descriptor link base address for RX channel
*/
static inline void gdma_ll_rx_set_desc_addr(gdma_dev_t *dev, uint32_t channel, uint32_t addr)
{
dev->channel[channel].in.in_link.addr = addr;
}
/**
* @brief Start dealing with RX descriptors
*/
static inline void gdma_ll_rx_start(gdma_dev_t *dev, uint32_t channel)
{
dev->channel[channel].in.in_link.start = 1;
}
/**
* @brief Stop dealing with RX descriptors
*/
static inline void gdma_ll_rx_stop(gdma_dev_t *dev, uint32_t channel)
{
dev->channel[channel].in.in_link.stop = 1;
}
/**
* @brief Restart a new inlink right after the last descriptor
*/
static inline void gdma_ll_rx_restart(gdma_dev_t *dev, uint32_t channel)
{
dev->channel[channel].in.in_link.restart = 1;
}
/**
* @brief Enable DMA RX to return the address of current descriptor when receives error
*/
static inline void gdma_ll_rx_enable_auto_return(gdma_dev_t *dev, uint32_t channel, bool enable)
{
dev->channel[channel].in.in_link.auto_ret = enable;
}
/**
* @brief Check if DMA RX FSM is in IDLE state
*/
static inline bool gdma_ll_rx_is_fsm_idle(gdma_dev_t *dev, uint32_t channel)
{
return dev->channel[channel].in.in_link.park;
}
/**
* @brief Get RX success EOF descriptor's address
*/
static inline uint32_t gdma_ll_rx_get_success_eof_desc_addr(gdma_dev_t *dev, uint32_t channel)
{
return dev->channel[channel].in.in_suc_eof_des_addr;
}
/**
* @brief Get RX error EOF descriptor's address
*/
static inline uint32_t gdma_ll_rx_get_error_eof_desc_addr(gdma_dev_t *dev, uint32_t channel)
{
return dev->channel[channel].in.in_err_eof_des_addr;
}
/**
* @brief Get current RX descriptor's address
*/
static inline uint32_t gdma_ll_rx_get_current_desc_addr(gdma_dev_t *dev, uint32_t channel)
{
return dev->channel[channel].in.in_dscr;
}
/**
* @brief Set priority for DMA RX channel
*/
static inline void gdma_ll_rx_set_priority(gdma_dev_t *dev, uint32_t channel, uint32_t prio)
{
dev->channel[channel].in.in_pri.rx_pri = prio;
}
/**
* @brief Connect DMA RX channel to a given peripheral
*/
static inline void gdma_ll_rx_connect_to_periph(gdma_dev_t *dev, uint32_t channel, int periph_id)
{
dev->channel[channel].in.in_peri_sel.sel = periph_id;
}
///////////////////////////////////// TX /////////////////////////////////////////
/**
* @brief Get DMA TX channel interrupt status word
*/
static inline uint32_t gdma_ll_tx_get_interrupt_status(gdma_dev_t *dev, uint32_t channel)
{
return dev->intr[channel].st.val & GDMA_LL_TX_EVENT_MASK;
}
/**
* @brief Enable DMA TX channel interrupt
*/
static inline void gdma_ll_tx_enable_interrupt(gdma_dev_t *dev, uint32_t channel, uint32_t mask, bool enable)
{
if (enable) {
dev->intr[channel].ena.val |= (mask & GDMA_LL_TX_EVENT_MASK);
} else {
dev->intr[channel].ena.val &= ~(mask & GDMA_LL_TX_EVENT_MASK);
}
}
/**
* @brief Clear DMA TX channel interrupt
*/
static inline void gdma_ll_tx_clear_interrupt_status(gdma_dev_t *dev, uint32_t channel, uint32_t mask)
{
dev->intr[channel].clr.val = (mask & GDMA_LL_TX_EVENT_MASK);
}
/**
* @brief Get DMA TX channel interrupt status register address
*/
static inline volatile void *gdma_ll_tx_get_interrupt_status_reg(gdma_dev_t *dev, uint32_t channel)
{
return (volatile void *)(&dev->intr[channel].st);
}
/**
* @brief Enable DMA TX channel to check the owner bit in the descriptor, disabled by default
*/
static inline void gdma_ll_tx_enable_owner_check(gdma_dev_t *dev, uint32_t channel, bool enable)
{
dev->channel[channel].out.out_conf1.out_check_owner = enable;
}
/**
* @brief Enable DMA TX channel burst sending data, disabled by default
*/
static inline void gdma_ll_tx_enable_data_burst(gdma_dev_t *dev, uint32_t channel, bool enable)
{
dev->channel[channel].out.out_conf0.out_data_burst_en = enable;
}
/**
* @brief Enable DMA TX channel burst reading descriptor link, disabled by default
*/
static inline void gdma_ll_tx_enable_descriptor_burst(gdma_dev_t *dev, uint32_t channel, bool enable)
{
dev->channel[channel].out.out_conf0.outdscr_burst_en = enable;
}
/**
* @brief Set TX channel EOF mode
*/
static inline void gdma_ll_tx_set_eof_mode(gdma_dev_t *dev, uint32_t channel, uint32_t mode)
{
dev->channel[channel].out.out_conf0.out_eof_mode = mode;
}
/**
* @brief Enable DMA TX channel automatic write results back to descriptor after all data has been sent out, disabled by default
*/
static inline void gdma_ll_tx_enable_auto_write_back(gdma_dev_t *dev, uint32_t channel, bool enable)
{
dev->channel[channel].out.out_conf0.out_auto_wrback = enable;
}
/**
* @brief Reset DMA TX channel FSM and FIFO pointer
*/
static inline void gdma_ll_tx_reset_channel(gdma_dev_t *dev, uint32_t channel)
{
dev->channel[channel].out.out_conf0.out_rst = 1;
dev->channel[channel].out.out_conf0.out_rst = 0;
}
/**
* @brief Check if DMA TX FIFO is full
* @param fifo_level only supports level 1
*/
static inline bool gdma_ll_tx_is_fifo_full(gdma_dev_t *dev, uint32_t channel, uint32_t fifo_level)
{
return dev->channel[channel].out.outfifo_status.val & 0x01;
}
/**
* @brief Check if DMA TX FIFO is empty
* @param fifo_level only supports level 1
*/
static inline bool gdma_ll_tx_is_fifo_empty(gdma_dev_t *dev, uint32_t channel, uint32_t fifo_level)
{
return dev->channel[channel].out.outfifo_status.val & 0x02;
}
/**
* @brief Get number of bytes in TX FIFO
* @param fifo_level only supports level 1
*/
static inline uint32_t gdma_ll_tx_get_fifo_bytes(gdma_dev_t *dev, uint32_t channel, uint32_t fifo_level)
{
return dev->channel[channel].out.outfifo_status.outfifo_cnt;
}
/**
* @brief Push data into DMA TX FIFO
*/
static inline void gdma_ll_tx_push_data(gdma_dev_t *dev, uint32_t channel, uint32_t data)
{
dev->channel[channel].out.out_push.outfifo_wdata = data;
dev->channel[channel].out.out_push.outfifo_push = 1;
}
/**
* @brief Set the descriptor link base address for TX channel
*/
static inline void gdma_ll_tx_set_desc_addr(gdma_dev_t *dev, uint32_t channel, uint32_t addr)
{
dev->channel[channel].out.out_link.addr = addr;
}
/**
* @brief Start dealing with TX descriptors
*/
static inline void gdma_ll_tx_start(gdma_dev_t *dev, uint32_t channel)
{
dev->channel[channel].out.out_link.start = 1;
}
/**
* @brief Stop dealing with TX descriptors
*/
static inline void gdma_ll_tx_stop(gdma_dev_t *dev, uint32_t channel)
{
dev->channel[channel].out.out_link.stop = 1;
}
/**
* @brief Restart a new outlink right after the last descriptor
*/
static inline void gdma_ll_tx_restart(gdma_dev_t *dev, uint32_t channel)
{
dev->channel[channel].out.out_link.restart = 1;
}
/**
* @brief Check if DMA TX FSM is in IDLE state
*/
static inline bool gdma_ll_tx_is_fsm_idle(gdma_dev_t *dev, uint32_t channel)
{
return dev->channel[channel].out.out_link.park;
}
/**
* @brief Get TX EOF descriptor's address
*/
static inline uint32_t gdma_ll_tx_get_eof_desc_addr(gdma_dev_t *dev, uint32_t channel)
{
return dev->channel[channel].out.out_eof_des_addr;
}
/**
* @brief Get current TX descriptor's address
*/
static inline uint32_t gdma_ll_tx_get_current_desc_addr(gdma_dev_t *dev, uint32_t channel)
{
return dev->channel[channel].out.out_dscr;
}
/**
* @brief Set priority for DMA TX channel
*/
static inline void gdma_ll_tx_set_priority(gdma_dev_t *dev, uint32_t channel, uint32_t prio)
{
dev->channel[channel].out.out_pri.tx_pri = prio;
}
/**
* @brief Connect DMA TX channel to a given peripheral
*/
static inline void gdma_ll_tx_connect_to_periph(gdma_dev_t *dev, uint32_t channel, int periph_id)
{
dev->channel[channel].out.out_peri_sel.sel = periph_id;
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,586 @@
// 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.
/*******************************************************************************
* NOTICE
* The hal is not public api, don't use in application code.
* See readme.md in soc/include/hal/readme.md
******************************************************************************/
// The LL layer for ESP32-C3 GPIO register operations
#pragma once
#include "soc/soc.h"
#include "soc/gpio_periph.h"
#include "soc/rtc_cntl_reg.h"
#include "hal/gpio_types.h"
#include "stdlib.h"
#ifdef __cplusplus
extern "C" {
#endif
/*
* The following defines are used to disable USB JTAG when pins 18 and pins 19
* are set to be used as GPIO.
* See gpio_pad_select_gpio() below.
*
* TODO: Delete these definitions once the USB device registers definition is
* merged.
*/
#define USB_DEVICE_CONF0_REG (0x60043018)
#define USB_DEVICE_USB_PAD_ENABLE (BIT(14))
// Get GPIO hardware instance with giving gpio num
#define GPIO_LL_GET_HW(num) (((num) == 0) ? (&GPIO) : NULL)
#define GPIO_LL_PRO_CPU_INTR_ENA (BIT(0))
#define GPIO_LL_PRO_CPU_NMI_INTR_ENA (BIT(1))
/**
* @brief Enable pull-up on GPIO.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_pullup_en(gpio_dev_t *hw, gpio_num_t gpio_num)
{
REG_SET_BIT(GPIO_PIN_MUX_REG[gpio_num], FUN_PU);
}
/**
* @brief Disable pull-up on GPIO.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_pullup_dis(gpio_dev_t *hw, gpio_num_t gpio_num)
{
REG_CLR_BIT(GPIO_PIN_MUX_REG[gpio_num], FUN_PU);
}
/**
* @brief Enable pull-down on GPIO.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_pulldown_en(gpio_dev_t *hw, gpio_num_t gpio_num)
{
REG_SET_BIT(GPIO_PIN_MUX_REG[gpio_num], FUN_PD);
}
/**
* @brief Disable pull-down on GPIO.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_pulldown_dis(gpio_dev_t *hw, gpio_num_t gpio_num)
{
REG_CLR_BIT(GPIO_PIN_MUX_REG[gpio_num], FUN_PD);
}
/**
* @brief GPIO set interrupt trigger type
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number. If you want to set the trigger type of e.g. of GPIO16, gpio_num should be GPIO_NUM_16 (16);
* @param intr_type Interrupt type, select from gpio_int_type_t
*/
static inline void gpio_ll_set_intr_type(gpio_dev_t *hw, gpio_num_t gpio_num, gpio_int_type_t intr_type)
{
hw->pin[gpio_num].int_type = intr_type;
}
/**
* @brief Get GPIO interrupt status
*
* @param hw Peripheral GPIO hardware instance address.
* @param core_id interrupt core id
* @param status interrupt status
*/
static inline void gpio_ll_get_intr_status(gpio_dev_t *hw, uint32_t core_id, uint32_t *status)
{
*status = hw->pcpu_int.intr;
}
/**
* @brief Get GPIO interrupt status high
*
* @param hw Peripheral GPIO hardware instance address.
* @param core_id interrupt core id
* @param status interrupt status high
*/
static inline void gpio_ll_get_intr_status_high(gpio_dev_t *hw, uint32_t core_id, uint32_t *status)
{
*status = 0; // Less than 32 GPIOs in ESP32-C3
}
/**
* @brief Clear GPIO interrupt status
*
* @param hw Peripheral GPIO hardware instance address.
* @param mask interrupt status clear mask
*/
static inline void gpio_ll_clear_intr_status(gpio_dev_t *hw, uint32_t mask)
{
hw->status_w1tc.status_w1tc = mask;
}
/**
* @brief Clear GPIO interrupt status high
*
* @param hw Peripheral GPIO hardware instance address.
* @param mask interrupt status high clear mask
*/
static inline void gpio_ll_clear_intr_status_high(gpio_dev_t *hw, uint32_t mask)
{
// Not supported on C3
}
/**
* @brief Enable GPIO module interrupt signal
*
* @param hw Peripheral GPIO hardware instance address.
* @param core_id Interrupt enabled CPU to corresponding ID
* @param gpio_num GPIO number. If you want to enable the interrupt of e.g. GPIO16, gpio_num should be GPIO_NUM_16 (16);
*/
static inline void gpio_ll_intr_enable_on_core(gpio_dev_t *hw, uint32_t core_id, gpio_num_t gpio_num)
{
if (core_id == 0) {
GPIO.pin[gpio_num].int_ena = GPIO_LL_PRO_CPU_INTR_ENA; //enable pro cpu intr
} else {
// GPIO.pin[gpio_num].int_ena = GPIO_APP_CPU_INTR_ENA; //enable pro cpu intr
}
}
/**
* @brief Disable GPIO module interrupt signal
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number. If you want to disable the interrupt of e.g. GPIO16, gpio_num should be GPIO_NUM_16 (16);
*/
static inline void gpio_ll_intr_disable(gpio_dev_t *hw, gpio_num_t gpio_num)
{
hw->pin[gpio_num].int_ena = 0; //disable GPIO intr
}
/**
* @brief Disable input mode on GPIO.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_input_disable(gpio_dev_t *hw, gpio_num_t gpio_num)
{
PIN_INPUT_DISABLE(GPIO_PIN_MUX_REG[gpio_num]);
}
/**
* @brief Enable input mode on GPIO.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_input_enable(gpio_dev_t *hw, gpio_num_t gpio_num)
{
PIN_INPUT_ENABLE(GPIO_PIN_MUX_REG[gpio_num]);
}
/**
* @brief Disable output mode on GPIO.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_output_disable(gpio_dev_t *hw, gpio_num_t gpio_num)
{
hw->enable_w1tc.enable_w1tc = (0x1 << gpio_num);
// Ensure no other output signal is routed via GPIO matrix to this pin
REG_WRITE(GPIO_FUNC0_OUT_SEL_CFG_REG + (gpio_num * 4),
SIG_GPIO_OUT_IDX);
}
/**
* @brief Enable output mode on GPIO.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_output_enable(gpio_dev_t *hw, gpio_num_t gpio_num)
{
hw->enable_w1ts.enable_w1ts = (0x1 << gpio_num);
}
/**
* @brief Disable open-drain mode on GPIO.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_od_disable(gpio_dev_t *hw, gpio_num_t gpio_num)
{
hw->pin[gpio_num].pad_driver = 0;
}
/**
* @brief Enable open-drain mode on GPIO.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_od_enable(gpio_dev_t *hw, gpio_num_t gpio_num)
{
hw->pin[gpio_num].pad_driver = 1;
}
/**
* @brief GPIO set output level
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number. If you want to set the output level of e.g. GPIO16, gpio_num should be GPIO_NUM_16 (16);
* @param level Output level. 0: low ; 1: high
*/
static inline void gpio_ll_set_level(gpio_dev_t *hw, gpio_num_t gpio_num, uint32_t level)
{
if (level) {
hw->out_w1ts.out_w1ts = (1 << gpio_num);
} else {
hw->out_w1tc.out_w1tc = (1 << gpio_num);
}
}
/**
* @brief GPIO get input level
*
* @warning If the pad is not configured for input (or input and output) the returned value is always 0.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number. If you want to get the logic level of e.g. pin GPIO16, gpio_num should be GPIO_NUM_16 (16);
*
* @return
* - 0 the GPIO input level is 0
* - 1 the GPIO input level is 1
*/
static inline int gpio_ll_get_level(gpio_dev_t *hw, gpio_num_t gpio_num)
{
return (hw->in.data >> gpio_num) & 0x1;
}
/**
* @brief Enable GPIO wake-up function.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number.
* @param intr_type GPIO wake-up type. Only GPIO_INTR_LOW_LEVEL or GPIO_INTR_HIGH_LEVEL can be used.
*/
static inline void gpio_ll_wakeup_enable(gpio_dev_t *hw, gpio_num_t gpio_num, gpio_int_type_t intr_type)
{
hw->pin[gpio_num].int_type = intr_type;
hw->pin[gpio_num].wakeup_enable = 0x1;
}
/**
* @brief Disable GPIO wake-up function.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_wakeup_disable(gpio_dev_t *hw, gpio_num_t gpio_num)
{
hw->pin[gpio_num].wakeup_enable = 0;
}
/**
* @brief Set GPIO pad drive capability
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number, only support output GPIOs
* @param strength Drive capability of the pad
*/
static inline void gpio_ll_set_drive_capability(gpio_dev_t *hw, gpio_num_t gpio_num, gpio_drive_cap_t strength)
{
SET_PERI_REG_BITS(GPIO_PIN_MUX_REG[gpio_num], FUN_DRV_V, strength, FUN_DRV_S);
}
/**
* @brief Get GPIO pad drive capability
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number, only support output GPIOs
* @param strength Pointer to accept drive capability of the pad
*/
static inline void gpio_ll_get_drive_capability(gpio_dev_t *hw, gpio_num_t gpio_num, gpio_drive_cap_t *strength)
{
*strength = GET_PERI_REG_BITS2(GPIO_PIN_MUX_REG[gpio_num], FUN_DRV_V, FUN_DRV_S);
}
/**
* @brief Enable all digital gpio pad hold function during Deep-sleep.
*
* @param hw Peripheral GPIO hardware instance address.
*/
static inline void gpio_ll_deep_sleep_hold_en(gpio_dev_t *hw)
{
SET_PERI_REG_MASK(RTC_CNTL_DIG_ISO_REG, RTC_CNTL_DG_PAD_AUTOHOLD_EN_M);
}
/**
* @brief Disable all digital gpio pad hold function during Deep-sleep.
*
* @param hw Peripheral GPIO hardware instance address.
*/
static inline void gpio_ll_deep_sleep_hold_dis(gpio_dev_t *hw)
{
SET_PERI_REG_MASK(RTC_CNTL_DIG_ISO_REG, RTC_CNTL_CLR_DG_PAD_AUTOHOLD);
}
/**
* @brief Enable gpio pad hold function.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number, only support output GPIOs
*/
static inline void gpio_ll_hold_en(gpio_dev_t *hw, gpio_num_t gpio_num)
{
if (gpio_num <= GPIO_NUM_5) {
REG_SET_BIT(RTC_CNTL_PAD_HOLD_REG, BIT(gpio_num));
} else {
SET_PERI_REG_MASK(RTC_CNTL_DIG_PAD_HOLD_REG, GPIO_HOLD_MASK[gpio_num]);
}
}
/**
* @brief Disable gpio pad hold function.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number, only support output GPIOs
*/
static inline void gpio_ll_hold_dis(gpio_dev_t *hw, gpio_num_t gpio_num)
{
if (gpio_num <= GPIO_NUM_5) {
REG_CLR_BIT(RTC_CNTL_PAD_HOLD_REG, BIT(gpio_num));
} else {
CLEAR_PERI_REG_MASK(RTC_CNTL_DIG_PAD_HOLD_REG, GPIO_HOLD_MASK[gpio_num]);
}
}
/**
* @brief Set pad input to a peripheral signal through the IOMUX.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number of the pad.
* @param signal_idx Peripheral signal id to input. One of the ``*_IN_IDX`` signals in ``soc/gpio_sig_map.h``.
*/
static inline void gpio_ll_iomux_in(gpio_dev_t *hw, uint32_t gpio, uint32_t signal_idx)
{
hw->func_in_sel_cfg[signal_idx].sig_in_sel = 0;
PIN_INPUT_ENABLE(GPIO_PIN_MUX_REG[gpio]);
}
/**
* @brief Select a function for the pin in the IOMUX
*
* @param pin_name Pin name to configure
* @param func Function to assign to the pin
*/
static inline void gpio_ll_iomux_func_sel(uint32_t pin_name, uint32_t func)
{
if (pin_name == IO_MUX_GPIO18_REG || pin_name == IO_MUX_GPIO19_REG) {
CLEAR_PERI_REG_MASK(USB_DEVICE_CONF0_REG, USB_DEVICE_USB_PAD_ENABLE);
}
PIN_FUNC_SELECT(pin_name, func);
}
/**
* @brief Set peripheral output to an GPIO pad through the IOMUX.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num gpio_num GPIO number of the pad.
* @param func The function number of the peripheral pin to output pin.
* One of the ``FUNC_X_*`` of specified pin (X) in ``soc/io_mux_reg.h``.
* @param oen_inv True if the output enable needs to be inverted, otherwise False.
*/
static inline void gpio_ll_iomux_out(gpio_dev_t *hw, uint8_t gpio_num, int func, uint32_t oen_inv)
{
hw->func_out_sel_cfg[gpio_num].oen_sel = 0;
hw->func_out_sel_cfg[gpio_num].oen_inv_sel = oen_inv;
gpio_ll_iomux_func_sel(GPIO_PIN_MUX_REG[gpio_num], func);
}
static inline void gpio_ll_force_hold_all(gpio_dev_t *hw)
{
CLEAR_PERI_REG_MASK(RTC_CNTL_DIG_ISO_REG, RTC_CNTL_DG_PAD_FORCE_UNHOLD);
SET_PERI_REG_MASK(RTC_CNTL_DIG_ISO_REG, RTC_CNTL_DG_PAD_FORCE_HOLD);
SET_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_PAD_FORCE_HOLD_M);
}
static inline void gpio_ll_force_unhold_all(void)
{
CLEAR_PERI_REG_MASK(RTC_CNTL_DIG_ISO_REG, RTC_CNTL_DG_PAD_FORCE_HOLD);
CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_PAD_FORCE_HOLD_M);
SET_PERI_REG_MASK(RTC_CNTL_DIG_ISO_REG, RTC_CNTL_DG_PAD_FORCE_UNHOLD);
SET_PERI_REG_MASK(RTC_CNTL_DIG_ISO_REG, RTC_CNTL_CLR_DG_PAD_AUTOHOLD);
}
/**
* @brief Enable GPIO pin used for wakeup from sleep.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_sleep_sel_en(gpio_dev_t *hw, gpio_num_t gpio_num)
{
PIN_SLP_SEL_ENABLE(GPIO_PIN_MUX_REG[gpio_num]);
}
/**
* @brief Disable GPIO pin used for wakeup from sleep.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_sleep_sel_dis(gpio_dev_t *hw, gpio_num_t gpio_num)
{
PIN_SLP_SEL_DISABLE(GPIO_PIN_MUX_REG[gpio_num]);
}
/**
* @brief Disable GPIO pull-up in sleep mode.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_sleep_pullup_dis(gpio_dev_t *hw, gpio_num_t gpio_num)
{
PIN_SLP_PULLUP_DISABLE(GPIO_PIN_MUX_REG[gpio_num]);
}
/**
* @brief Enable GPIO pull-up in sleep mode.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_sleep_pullup_en(gpio_dev_t *hw, gpio_num_t gpio_num)
{
PIN_SLP_PULLUP_ENABLE(GPIO_PIN_MUX_REG[gpio_num]);
}
/**
* @brief Enable GPIO pull-down in sleep mode.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_sleep_pulldown_en(gpio_dev_t *hw, gpio_num_t gpio_num)
{
PIN_SLP_PULLDOWN_ENABLE(GPIO_PIN_MUX_REG[gpio_num]);
}
/**
* @brief Disable GPIO pull-down in sleep mode.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_sleep_pulldown_dis(gpio_dev_t *hw, gpio_num_t gpio_num)
{
PIN_SLP_PULLDOWN_DISABLE(GPIO_PIN_MUX_REG[gpio_num]);
}
/**
* @brief Disable GPIO input in sleep mode.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_sleep_input_disable(gpio_dev_t *hw, gpio_num_t gpio_num)
{
PIN_SLP_INPUT_DISABLE(GPIO_PIN_MUX_REG[gpio_num]);
}
/**
* @brief Enable GPIO input in sleep mode.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_sleep_input_enable(gpio_dev_t *hw, gpio_num_t gpio_num)
{
PIN_SLP_INPUT_ENABLE(GPIO_PIN_MUX_REG[gpio_num]);
}
/**
* @brief Disable GPIO output in sleep mode.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_sleep_output_disable(gpio_dev_t *hw, gpio_num_t gpio_num)
{
PIN_SLP_OUTPUT_DISABLE(GPIO_PIN_MUX_REG[gpio_num]);
}
/**
* @brief Enable GPIO output in sleep mode.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_sleep_output_enable(gpio_dev_t *hw, gpio_num_t gpio_num)
{
PIN_SLP_OUTPUT_ENABLE(GPIO_PIN_MUX_REG[gpio_num]);
}
/**
* @brief Enable GPIO deep-sleep wake-up function.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number.
* @param intr_type GPIO wake-up type. Only GPIO_INTR_LOW_LEVEL or GPIO_INTR_HIGH_LEVEL can be used.
*/
static inline void gpio_ll_deepsleep_wakeup_enable(gpio_dev_t *hw, gpio_num_t gpio_num, gpio_int_type_t intr_type)
{
if (gpio_num > GPIO_NUM_5) {
abort(); // gpio lager than 5 doesn't support.
}
REG_SET_BIT(RTC_CNTL_GPIO_WAKEUP_REG, RTC_CNTL_GPIO_PIN_CLK_GATE);
REG_SET_BIT(RTC_CNTL_EXT_WAKEUP_CONF_REG, RTC_CNTL_GPIO_WAKEUP_FILTER);
SET_PERI_REG_MASK(RTC_CNTL_GPIO_WAKEUP_REG, 1 << (RTC_CNTL_GPIO_PIN0_WAKEUP_ENABLE_S - gpio_num));
uint32_t reg = REG_READ(RTC_CNTL_GPIO_WAKEUP_REG);
reg &= (~(RTC_CNTL_GPIO_PIN0_INT_TYPE_V << (RTC_CNTL_GPIO_PIN0_INT_TYPE_S - gpio_num * 3)));
reg |= (intr_type << (RTC_CNTL_GPIO_PIN0_INT_TYPE_S - gpio_num * 3));
REG_WRITE(RTC_CNTL_GPIO_WAKEUP_REG, reg);
}
/**
* @brief Disable GPIO deep-sleep wake-up function.
*
* @param hw Peripheral GPIO hardware instance address.
* @param gpio_num GPIO number
*/
static inline void gpio_ll_deepsleep_wakeup_disable(gpio_dev_t *hw, gpio_num_t gpio_num)
{
if (gpio_num > GPIO_NUM_5) {
abort(); // gpio lager than 5 doesn't support.
}
CLEAR_PERI_REG_MASK(RTC_CNTL_GPIO_WAKEUP_REG, 1 << (RTC_CNTL_GPIO_PIN0_WAKEUP_ENABLE_S - gpio_num));
CLEAR_PERI_REG_MASK(RTC_CNTL_GPIO_WAKEUP_REG, RTC_CNTL_GPIO_PIN0_INT_TYPE_S - gpio_num * 3);
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,394 @@
// 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.
/*******************************************************************************
* NOTICE
* The ll is not public api, don't use in application code.
* See readme.md in soc/include/hal/readme.md
******************************************************************************/
// The Lowlevel layer for SPI Flash
#pragma once
#include <stdlib.h>
#include "soc/spi_periph.h"
#include "hal/spi_types.h"
#include "hal/spi_flash_types.h"
#include <sys/param.h> // For MIN/MAX
#include <stdbool.h>
#include <string.h>
#ifdef __cplusplus
extern "C" {
#endif
//NOTE: These macros are changed on c3 for build. MODIFY these when bringup flash.
#define gpspi_flash_ll_get_hw(host_id) ( ((host_id)==SPI2_HOST) ? &GPSPI2 : ({abort();(spi_dev_t*)0;}) )
#define gpspi_flash_ll_hw_get_id(dev) ( ((dev) == (void*)&GPSPI2) ? SPI2_HOST : -1 )
typedef typeof(GPSPI2.clock) gpspi_flash_ll_clock_reg_t;
//Supported clock register values
#define GPSPI_FLASH_LL_CLKREG_VAL_5MHZ ((gpspi_flash_ll_clock_reg_t){.val=0x0000F1CF}) ///< Clock set to 5 MHz
#define GPSPI_FLASH_LL_CLKREG_VAL_10MHZ ((gpspi_flash_ll_clock_reg_t){.val=0x000070C7}) ///< Clock set to 10 MHz
#define GPSPI_FLASH_LL_CLKREG_VAL_20MHZ ((gpspi_flash_ll_clock_reg_t){.val=0x00003043}) ///< Clock set to 20 MHz
#define GPSPI_FLASH_LL_CLKREG_VAL_26MHZ ((gpspi_flash_ll_clock_reg_t){.val=0x00002002}) ///< Clock set to 26 MHz
#define GPSPI_FLASH_LL_CLKREG_VAL_40MHZ ((gpspi_flash_ll_clock_reg_t){.val=0x00001001}) ///< Clock set to 40 MHz
#define GPSPI_FLASH_LL_CLKREG_VAL_80MHZ ((gpspi_flash_ll_clock_reg_t){.val=0x80000000}) ///< Clock set to 80 MHz
/*------------------------------------------------------------------------------
* Control
*----------------------------------------------------------------------------*/
/**
* Reset peripheral registers before configuration and starting control
*
* @param dev Beginning address of the peripheral registers.
*/
static inline void gpspi_flash_ll_reset(spi_dev_t *dev)
{
dev->user.val = 0;
dev->ctrl.val = 0;
dev->clk_gate.clk_en = 1;
dev->clk_gate.mst_clk_active = 1;
dev->clk_gate.mst_clk_sel = 1;
dev->dma_conf.val = 0;
dev->dma_conf.tx_seg_trans_clr_en = 1;
dev->dma_conf.rx_seg_trans_clr_en = 1;
dev->dma_conf.dma_seg_trans_en = 0;
}
/**
* Check whether the previous operation is done.
*
* @param dev Beginning address of the peripheral registers.
*
* @return true if last command is done, otherwise false.
*/
static inline bool gpspi_flash_ll_cmd_is_done(const spi_dev_t *dev)
{
return (dev->cmd.usr == 0);
}
/**
* Get the read data from the buffer after ``gpspi_flash_ll_read`` is done.
*
* @param dev Beginning address of the peripheral registers.
* @param buffer Buffer to hold the output data
* @param read_len Length to get out of the buffer
*/
static inline void gpspi_flash_ll_get_buffer_data(spi_dev_t *dev, void *buffer, uint32_t read_len)
{
if (((intptr_t)buffer % 4 == 0) && (read_len % 4 == 0)) {
// If everything is word-aligned, do a faster memcpy
memcpy(buffer, (void *)dev->data_buf, read_len);
} else {
// Otherwise, slow(er) path copies word by word
int copy_len = read_len;
for (int i = 0; i < (read_len + 3) / 4; i++) {
int word_len = MIN(sizeof(uint32_t), copy_len);
uint32_t word = dev->data_buf[i];
memcpy(buffer, &word, word_len);
buffer = (void *)((intptr_t)buffer + word_len);
copy_len -= word_len;
}
}
}
/**
* Write a word to the data buffer.
*
* @param dev Beginning address of the peripheral registers.
* @param word Data to write at address 0.
*/
static inline void gpspi_flash_ll_write_word(spi_dev_t *dev, uint32_t word)
{
dev->data_buf[0] = word;
}
/**
* Set the data to be written in the data buffer.
*
* @param dev Beginning address of the peripheral registers.
* @param buffer Buffer holding the data
* @param length Length of data in bytes.
*/
static inline void gpspi_flash_ll_set_buffer_data(spi_dev_t *dev, const void *buffer, uint32_t length)
{
// Load data registers, word at a time
int num_words = (length + 3) / 4;
for (int i = 0; i < num_words; i++) {
uint32_t word = 0;
uint32_t word_len = MIN(length, sizeof(word));
memcpy(&word, buffer, word_len);
dev->data_buf[i] = word;
length -= word_len;
buffer = (void *)((intptr_t)buffer + word_len);
}
}
/**
* Trigger a user defined transaction. All phases, including command, address, dummy, and the data phases,
* should be configured before this is called.
*
* @param dev Beginning address of the peripheral registers.
*/
static inline void gpspi_flash_ll_user_start(spi_dev_t *dev)
{
dev->ctrl.hold_pol = 1;
dev->cmd.update = 1;
while (dev->cmd.update);
dev->cmd.usr = 1;
}
/**
* Check whether the host is idle to perform new commands.
*
* @param dev Beginning address of the peripheral registers.
*
* @return true if the host is idle, otherwise false
*/
static inline bool gpspi_flash_ll_host_idle(const spi_dev_t *dev)
{
return dev->cmd.usr == 0;
}
/**
* Set phases for user-defined transaction to read
*
* @param dev Beginning address of the peripheral registers.
*/
static inline void gpspi_flash_ll_read_phase(spi_dev_t *dev)
{
typeof (dev->user) user = {
.usr_command = 1,
.usr_mosi = 0,
.usr_miso = 1,
.usr_addr = 1,
};
dev->user = user;
}
/*------------------------------------------------------------------------------
* Configs
*----------------------------------------------------------------------------*/
/**
* Select which pin to use for the flash
*
* @param dev Beginning address of the peripheral registers.
* @param pin Pin ID to use, 0-2. Set to other values to disable all the CS pins.
*/
static inline void gpspi_flash_ll_set_cs_pin(spi_dev_t *dev, int pin)
{
dev->misc.cs0_dis = (pin == 0) ? 0 : 1;
dev->misc.cs1_dis = (pin == 1) ? 0 : 1;
}
/**
* Set the read io mode.
*
* @param dev Beginning address of the peripheral registers.
* @param read_mode I/O mode to use in the following transactions.
*/
static inline void gpspi_flash_ll_set_read_mode(spi_dev_t *dev, esp_flash_io_mode_t read_mode)
{
typeof (dev->ctrl) ctrl = dev->ctrl;
typeof (dev->user) user = dev->user;
ctrl.val &= ~(SPI_FCMD_QUAD_M | SPI_FADDR_QUAD_M | SPI_FREAD_QUAD_M | SPI_FCMD_DUAL_M | SPI_FADDR_DUAL_M | SPI_FREAD_DUAL_M);
user.val &= ~(SPI_FWRITE_QUAD_M | SPI_FWRITE_DUAL_M);
switch (read_mode) {
case SPI_FLASH_FASTRD:
//the default option
case SPI_FLASH_SLOWRD:
break;
case SPI_FLASH_QIO:
ctrl.fread_quad = 1;
ctrl.faddr_quad = 1;
user.fwrite_quad = 1;
break;
case SPI_FLASH_QOUT:
ctrl.fread_quad = 1;
user.fwrite_quad = 1;
break;
case SPI_FLASH_DIO:
ctrl.fread_dual = 1;
ctrl.faddr_dual = 1;
user.fwrite_dual = 1;
break;
case SPI_FLASH_DOUT:
ctrl.fread_dual = 1;
user.fwrite_dual = 1;
break;
default:
abort();
}
dev->ctrl = ctrl;
dev->user = user;
}
/**
* Set clock frequency to work at.
*
* @param dev Beginning address of the peripheral registers.
* @param clock_val pointer to the clock value to set
*/
static inline void gpspi_flash_ll_set_clock(spi_dev_t *dev, gpspi_flash_ll_clock_reg_t *clock_val)
{
dev->clock = *clock_val;
}
/**
* Set the input length, in bits.
*
* @param dev Beginning address of the peripheral registers.
* @param bitlen Length of input, in bits.
*/
static inline void gpspi_flash_ll_set_miso_bitlen(spi_dev_t *dev, uint32_t bitlen)
{
dev->user.usr_miso = bitlen > 0;
if (bitlen) {
dev->ms_dlen.ms_data_bitlen = bitlen - 1;
}
}
/**
* Set the output length, in bits (not including command, address and dummy
* phases)
*
* @param dev Beginning address of the peripheral registers.
* @param bitlen Length of output, in bits.
*/
static inline void gpspi_flash_ll_set_mosi_bitlen(spi_dev_t *dev, uint32_t bitlen)
{
dev->user.usr_mosi = bitlen > 0;
if (bitlen) {
dev->ms_dlen.ms_data_bitlen = bitlen - 1;
}
}
/**
* Set the command.
*
* @param dev Beginning address of the peripheral registers.
* @param command Command to send
* @param bitlen Length of the command
*/
static inline void gpspi_flash_ll_set_command(spi_dev_t *dev, uint8_t command, uint32_t bitlen)
{
dev->user.usr_command = 1;
typeof(dev->user2) user2 = {
.usr_command_value = command,
.usr_command_bitlen = (bitlen - 1),
};
dev->user2 = user2;
}
/**
* Get the address length that is set in register, in bits.
*
* @param dev Beginning address of the peripheral registers.
*
*/
static inline int gpspi_flash_ll_get_addr_bitlen(spi_dev_t *dev)
{
return dev->user.usr_addr ? dev->user1.usr_addr_bitlen + 1 : 0;
}
/**
* Set the address length to send, in bits. Should be called before commands that requires the address e.g. erase sector, read, write...
*
* @param dev Beginning address of the peripheral registers.
* @param bitlen Length of the address, in bits
*/
static inline void gpspi_flash_ll_set_addr_bitlen(spi_dev_t *dev, uint32_t bitlen)
{
dev->user1.usr_addr_bitlen = (bitlen - 1);
dev->user.usr_addr = bitlen ? 1 : 0;
}
/**
* Set the address to send in user mode. Should be called before commands that requires the address e.g. erase sector, read, write...
*
* @param dev Beginning address of the peripheral registers.
* @param addr Address to send
*/
static inline void gpspi_flash_ll_set_usr_address(spi_dev_t *dev, uint32_t addr, uint32_t bitlen)
{
// The blank region should be all ones
uint32_t padding_ones = (bitlen == 32? 0 : UINT32_MAX >> bitlen);
dev->addr = (addr << (32 - bitlen)) | padding_ones;
}
/**
* Set the address to send. Should be called before commands that requires the address e.g. erase sector, read, write...
*
* @param dev Beginning address of the peripheral registers.
* @param addr Address to send
*/
static inline void gpspi_flash_ll_set_address(spi_dev_t *dev, uint32_t addr)
{
dev->addr = addr;
}
/**
* Set the length of dummy cycles.
*
* @param dev Beginning address of the peripheral registers.
* @param dummy_n Cycles of dummy phases
*/
static inline void gpspi_flash_ll_set_dummy(spi_dev_t *dev, uint32_t dummy_n)
{
dev->user.usr_dummy = dummy_n ? 1 : 0;
dev->user1.usr_dummy_cyclelen = dummy_n - 1;
}
/**
* Set D/Q output level during dummy phase
*
* @param dev Beginning address of the peripheral registers.
* @param out_en whether to enable IO output for dummy phase
* @param out_level dummy output level
*/
static inline void gpspi_flash_ll_set_dummy_out(spi_dev_t *dev, uint32_t out_en, uint32_t out_lev)
{
dev->ctrl.dummy_out = out_en;
dev->ctrl.q_pol = out_lev;
dev->ctrl.d_pol = out_lev;
}
/**
* Set extra hold time of CS after the clocks.
*
* @param dev Beginning address of the peripheral registers.
* @param hold_n Cycles of clocks before CS is inactive
*/
static inline void gpspi_flash_ll_set_hold(spi_dev_t *dev, uint32_t hold_n)
{
dev->user1.cs_hold_time = hold_n - 1;
dev->user.cs_hold = (hold_n > 0? 1: 0);
}
static inline void gpspi_flash_ll_set_cs_setup(spi_dev_t *dev, uint32_t cs_setup_time)
{
dev->user.cs_setup = (cs_setup_time > 0 ? 1 : 0);
dev->user1.cs_setup_time = cs_setup_time - 1;
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,109 @@
// 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.
/*******************************************************************************
* NOTICE
* The hal is not public api, don't use it in application code.
* See readme.md in soc/include/hal/readme.md
******************************************************************************/
#pragma once
#include <stdint.h>
#include <stdbool.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* The HMAC peripheral can be configured to deliver its output to the user directly, or to deliver
* the output directly to another peripheral instead, e.g. the Digital Signature peripheral.
*/
typedef enum {
HMAC_OUTPUT_USER = 0, /**< Let user provide a message and read the HMAC result */
HMAC_OUTPUT_DS = 1, /**< HMAC is provided to the DS peripheral to decrypt DS private key parameters */
HMAC_OUTPUT_JTAG_ENABLE = 2, /**< HMAC is used to enable JTAG after soft-disabling it */
HMAC_OUTPUT_ALL = 3 /**< HMAC is used for both as DS input for or enabling JTAG */
} hmac_hal_output_t;
/**
* @brief Make the peripheral ready for use.
*
* This triggers any further steps necessary after enabling the device
*/
void hmac_hal_start(void);
/**
* @brief Configure which hardware key slot should be used and configure the target of the HMAC output.
*
* @note Writing out-of-range values is undefined behavior. The user has to ensure that the parameters are in range.
*
* @param config The target of the HMAC. Possible targets are described in \c hmac_hal_output_t.
* See the ESP32C3 TRM for more details.
* @param key_id The ID of the hardware key slot to be used.
*
* @return 0 if the configuration was successful, non-zero if not.
* An unsuccessful configuration means that the purpose value in the eFuse of the corresponding key slot
* doesn't match to supplied value of \c config.
*/
uint32_t hmac_hal_configure(hmac_hal_output_t config, uint32_t key_id);
/**
* @brief Write a padded single-block message of 512 bits to the HMAC peripheral.
*
* The message must not be longer than one block (512 bits) and the padding has to be applied by software before
* writing. The padding has to be able to fit into the block after the message.
* For more information on HMAC padding, see the ESP32C3 TRM.
*/
void hmac_hal_write_one_block_512(const void *block);
/**
* @brief Write a message block of 512 bits to the HMAC peripheral.
*
* This function must be used incombination with \c hmac_hal_next_block_normal() or \c hmac_hal_next_block_padding().
* The first message block is written without any prerequisite.
* All message blocks which are not the last one, need a call to \c hmac_hal_next_block_normal() before, indicating
* to the hardware that a "normal", i.e. non-padded block will follow. This is even the case for a block which begins
* padding already but where the padding doesn't fit in (remaining message size > (block size - padding size)).
* Before writing the last block which contains the padding, a call to \c hmac_hal_next_block_padding() is necessary
* to indicate to the hardware that a block with padding will be written.
*
* For more information on HMAC padding, see the ESP32C3 TRM.
*/
void hmac_hal_write_block_512(const void *block);
/**
* @brief Indicate to the hardware that a normal block will be written.
*/
void hmac_hal_next_block_normal(void);
/**
* @brief Indicate to the hardware that a block with padding will be written.
*/
void hmac_hal_next_block_padding(void);
/**
* @brief Read the 256 bit HMAC result from the hardware.
*/
void hmac_hal_read_result_256(void *result);
/**
* @brief Clear (invalidate) the HMAC result provided to other hardware.
*/
void hmac_hal_clean(void);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,199 @@
// 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.
/*******************************************************************************
* NOTICE
* The hal is not public api, don't use it in application code.
* See readme.md in soc/include/hal/readme.md
******************************************************************************/
#pragma once
#include <string.h>
#include "soc/system_reg.h"
#include "soc/hwcrypto_reg.h"
#include "hal/hmac_hal.h"
#define SHA256_BLOCK_SZ 64
#define SHA256_DIGEST_SZ 32
#define EFUSE_KEY_PURPOSE_HMAC_DOWN_JTAG 6
#define EFUSE_KEY_PURPOSE_HMAC_DOWN_DIGITAL_SIGNATURE 7
#define EFUSE_KEY_PURPOSE_HMAC_UP 8
#define EFUSE_KEY_PURPOSE_HMAC_DOWN_ALL 5
#ifdef __cplusplus
extern "C" {
#endif
/**
* Makes the peripheral ready for use, after enabling it.
*/
static inline void hmac_ll_start(void)
{
REG_WRITE(HMAC_SET_START_REG, 1);
}
/**
* @brief Determine where the HMAC output should go.
*
* The HMAC peripheral can be configured to deliver its output to the user directly, or to deliver
* the output directly to another peripheral instead, e.g. the Digital Signature peripheral.
*/
static inline void hmac_ll_config_output(hmac_hal_output_t config)
{
switch(config) {
case HMAC_OUTPUT_USER:
REG_WRITE(HMAC_SET_PARA_PURPOSE_REG, EFUSE_KEY_PURPOSE_HMAC_UP);
break;
case HMAC_OUTPUT_DS:
REG_WRITE(HMAC_SET_PARA_PURPOSE_REG, EFUSE_KEY_PURPOSE_HMAC_DOWN_DIGITAL_SIGNATURE);
break;
case HMAC_OUTPUT_JTAG_ENABLE:
REG_WRITE(HMAC_SET_PARA_PURPOSE_REG, EFUSE_KEY_PURPOSE_HMAC_DOWN_JTAG);
break;
case HMAC_OUTPUT_ALL:
REG_WRITE(HMAC_SET_PARA_PURPOSE_REG, EFUSE_KEY_PURPOSE_HMAC_DOWN_ALL);
break;
default:
; // do nothing, error will be indicated by hmac_hal_config_error()
}
}
/**
* @brief Selects which hardware key should be used.
*/
static inline void hmac_ll_config_hw_key_id(uint32_t key_id)
{
REG_WRITE(HMAC_SET_PARA_KEY_REG, key_id);
}
/**
* @brief Apply and check configuration.
*
* Afterwards, the configuration can be checked for errors with hmac_hal_config_error().
*/
static inline void hmac_ll_config_finish(void)
{
REG_WRITE(HMAC_SET_PARA_FINISH_REG, 1);
}
/**
*
* @brief Query HMAC error state after configuration actions.
*
* @return
* - 1 or greater on error
* - 0 on success
*/
static inline uint32_t hmac_ll_config_error(void)
{
return REG_READ(HMAC_QUERY_ERROR_REG);
}
/**
* Wait until the HAL is ready for the next interaction.
*/
static inline void hmac_ll_wait_idle(void)
{
uint32_t query;
do {
query = REG_READ(HMAC_QUERY_BUSY_REG);
} while(query != 0);
}
/**
* @brief Write a message block of 512 bits to the HMAC peripheral.
*/
static inline void hmac_ll_write_block_512(const uint32_t *block)
{
const size_t REG_WIDTH = sizeof(uint32_t);
for (size_t i = 0; i < SHA256_BLOCK_SZ / REG_WIDTH; i++) {
REG_WRITE(HMAC_WDATA_BASE + (i * REG_WIDTH), block[i]);
}
REG_WRITE(HMAC_SET_MESSAGE_ONE_REG, 1);
}
/**
* @brief Read the 256 bit HMAC.
*/
static inline void hmac_ll_read_result_256(uint32_t *result)
{
const size_t REG_WIDTH = sizeof(uint32_t);
for (size_t i = 0; i < SHA256_DIGEST_SZ / REG_WIDTH; i++) {
result[i] = REG_READ(HMAC_RDATA_BASE + (i * REG_WIDTH));
}
}
/**
* @brief Clean the HMAC result provided to other hardware.
*/
static inline void hmac_ll_clean(void)
{
REG_WRITE(HMAC_SET_INVALIDATE_DS_REG, 1);
REG_WRITE(HMAC_SET_INVALIDATE_JTAG_REG, 1);
}
/**
* @brief Signals that the following block will be the padded last block.
*/
static inline void hmac_ll_msg_padding(void)
{
REG_WRITE(HMAC_SET_MESSAGE_PAD_REG, 1);
}
/**
* @brief Signals that all blocks have been written and a padding block will automatically be applied by hardware.
*
* Only applies if the message length is a multiple of 512 bits.
* See ESP32C3 TRM HMAC chapter for more details.
*/
static inline void hmac_ll_msg_end(void)
{
REG_WRITE(HMAC_SET_MESSAGE_END_REG, 1);
}
/**
* @brief The message including padding fits into one block, so no further action needs to be taken.
*
* This is called after the one-block-message has been written.
*/
static inline void hmac_ll_msg_one_block(void)
{
REG_WRITE(HMAC_ONE_BLOCK_REG, 1);
}
/**
* @brief Indicate that more blocks will be written after the last block.
*/
static inline void hmac_ll_msg_continue(void)
{
REG_WRITE(HMAC_SET_MESSAGE_ING_REG, 1);
}
/**
* @brief Clear the HMAC result.
*
* Use this after reading the HMAC result or if aborting after any of the other steps above.
*/
static inline void hmac_ll_calc_finish(void)
{
REG_WRITE(HMAC_SET_RESULT_FINISH_REG, 2);
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,914 @@
// 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.
// The LL layer for I2C register operations
#pragma once
#include "soc/i2c_periph.h"
#include "soc/soc_caps.h"
#include "hal/i2c_types.h"
#include "soc/rtc_cntl_reg.h"
#include "esp_rom_sys.h"
#ifdef __cplusplus
extern "C" {
#endif
#define I2C_LL_INTR_MASK (0x3fff) /*!< I2C all interrupt bitmap */
/**
* @brief I2C hardware cmd register filed.
*/
typedef union {
struct {
uint32_t byte_num: 8,
ack_en: 1,
ack_exp: 1,
ack_val: 1,
op_code: 3,
reserved14: 17,
done: 1;
};
uint32_t val;
} i2c_hw_cmd_t;
/**
* @brief I2C interrupt event
*/
typedef enum {
I2C_INTR_EVENT_ERR,
I2C_INTR_EVENT_ARBIT_LOST, /*!< I2C arbition lost event */
I2C_INTR_EVENT_NACK, /*!< I2C NACK event */
I2C_INTR_EVENT_TOUT, /*!< I2C time out event */
I2C_INTR_EVENT_END_DET, /*!< I2C end detected event */
I2C_INTR_EVENT_TRANS_DONE, /*!< I2C trans done event */
I2C_INTR_EVENT_RXFIFO_FULL, /*!< I2C rxfifo full event */
I2C_INTR_EVENT_TXFIFO_EMPTY, /*!< I2C txfifo empty event */
} i2c_intr_event_t;
/**
* @brief Data structure for calculating I2C bus timing.
*/
typedef struct {
uint16_t clkm_div; /*!< I2C core clock devider */
uint16_t scl_low; /*!< I2C scl low period */
uint16_t scl_high; /*!< I2C scl hight period */
uint16_t scl_wait_high; /*!< I2C scl wait_high period */
uint16_t sda_hold; /*!< I2C scl low period */
uint16_t sda_sample; /*!< I2C sda sample time */
uint16_t setup; /*!< I2C start and stop condition setup period */
uint16_t hold; /*!< I2C start and stop condition hold period */
uint16_t tout; /*!< I2C bus timeout period */
} i2c_clk_cal_t;
// I2C operation mode command
#define I2C_LL_CMD_RESTART 6 /*!<I2C restart command */
#define I2C_LL_CMD_WRITE 1 /*!<I2C write command */
#define I2C_LL_CMD_READ 3 /*!<I2C read command */
#define I2C_LL_CMD_STOP 2 /*!<I2C stop command */
#define I2C_LL_CMD_END 4 /*!<I2C end command */
// Get the I2C hardware instance
#define I2C_LL_GET_HW(i2c_num) (&I2C0)
// Get the I2C hardware FIFO address
#define I2C_LL_GET_FIFO_ADDR(i2c_num) (I2C_DATA_APB_REG(i2c_num))
// I2C master TX interrupt bitmap
#define I2C_LL_MASTER_TX_INT (I2C_NACK_INT_ENA_M|I2C_TIME_OUT_INT_ENA_M|I2C_TRANS_COMPLETE_INT_ENA_M|I2C_ARBITRATION_LOST_INT_ENA_M|I2C_END_DETECT_INT_ENA_M)
// I2C master RX interrupt bitmap
#define I2C_LL_MASTER_RX_INT (I2C_TIME_OUT_INT_ENA_M|I2C_TRANS_COMPLETE_INT_ENA_M|I2C_ARBITRATION_LOST_INT_ENA_M|I2C_END_DETECT_INT_ENA_M)
// I2C slave TX interrupt bitmap
#define I2C_LL_SLAVE_TX_INT (I2C_TXFIFO_WM_INT_ENA_M)
// I2C slave RX interrupt bitmap
#define I2C_LL_SLAVE_RX_INT (I2C_RXFIFO_WM_INT_ENA_M | I2C_TRANS_COMPLETE_INT_ENA_M)
// I2C source clock
#define I2C_LL_CLK_SRC_FREQ(src_clk) (((src_clk) == I2C_SCLK_RTC) ? 20*1000*1000 : 40*1000*1000); // Another clock is XTAL clock
// delay time after rtc_clk swiching on
#define DELAY_RTC_CLK_SWITCH (5)
// I2C max timeout value
#define I2C_LL_MAX_TIMEOUT I2C_TIME_OUT_REG_V
/**
* @brief Calculate I2C bus frequency
* Note that the clock accuracy is affected by the external pull-up resistor,
* here we try to to calculate a configuration parameter which is close to the required clock.
* But in I2C communication, the clock accuracy is not very concerned.
*
* @param source_clk I2C source clock
* @param bus_freq I2C bus frequency
* @param clk_cal Pointer to accept the clock configuration
*
* @return None
*/
static inline void i2c_ll_cal_bus_clk(uint32_t source_clk, uint32_t bus_freq, i2c_clk_cal_t *clk_cal)
{
uint32_t clkm_div = source_clk / (bus_freq * 1024) +1;
uint32_t sclk_freq = source_clk / clkm_div;
uint32_t half_cycle = sclk_freq / bus_freq / 2;
//SCL
clk_cal->clkm_div = clkm_div;
clk_cal->scl_low = half_cycle;
// default, scl_wait_high < scl_high
int scl_wait_high = (bus_freq <= 50000) ? 0 : (half_cycle / 8); // compensate the time when freq > 50K
clk_cal->scl_wait_high = scl_wait_high;
clk_cal->scl_high = half_cycle - scl_wait_high;
clk_cal->sda_hold = half_cycle / 4;
// scl_wait_high < sda_sample <= scl_high
clk_cal->sda_sample = half_cycle / 2;
clk_cal->setup = half_cycle;
clk_cal->hold = half_cycle;
//default we set the timeout value to about 10 bus cycles
// log(20*half_cycle)/log(2) = log(half_cycle)/log(2) + log(20)/log(2)
clk_cal->tout = (int)(sizeof(half_cycle) * 8 - __builtin_clz(5 * half_cycle)) + 2;
}
/**
* @brief Update I2C configuration
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_update(i2c_dev_t *hw)
{
hw->ctr.conf_upgate = 1;
}
/**
* @brief Configure the I2C bus timing related register.
*
* @param hw Beginning address of the peripheral registers
* @param bus_cfg Pointer to the data structure holding the register configuration.
*
* @return None
*/
static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_clk_cal_t *bus_cfg)
{
hw->clk_conf.sclk_div_num = bus_cfg->clkm_div - 1;
//scl period
hw->scl_low_period.period = bus_cfg->scl_low - 1;
hw->scl_high_period.period = bus_cfg->scl_high;
//sda sample
hw->sda_hold.time = bus_cfg->sda_hold;
hw->sda_sample.time = bus_cfg->sda_sample;
//setup
hw->scl_rstart_setup.time = bus_cfg->setup;
hw->scl_stop_setup.time = bus_cfg->setup;
//hold
hw->scl_start_hold.time = bus_cfg->hold - 1;
hw->scl_stop_hold.time = bus_cfg->hold;
hw->timeout.time_out_value = bus_cfg->tout;
hw->timeout.time_out_en = 1;
}
/**
* @brief Reset I2C txFIFO
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_txfifo_rst(i2c_dev_t *hw)
{
hw->fifo_conf.tx_fifo_rst = 1;
hw->fifo_conf.tx_fifo_rst = 0;
}
/**
* @brief Reset I2C rxFIFO
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_rxfifo_rst(i2c_dev_t *hw)
{
hw->fifo_conf.rx_fifo_rst = 1;
hw->fifo_conf.rx_fifo_rst = 0;
}
/**
* @brief Configure I2C SCL timing
*
* @param hw Beginning address of the peripheral registers
* @param hight_period The I2C SCL hight period (in core clock cycle, hight_period > 2)
* @param low_period The I2C SCL low period (in core clock cycle, low_period > 1)
*
* @return None.
*/
static inline void i2c_ll_set_scl_timing(i2c_dev_t *hw, int hight_period, int low_period)
{
hw->scl_low_period.period = low_period - 1;
hw->scl_high_period.period = hight_period - 10;
hw->scl_high_period.scl_wait_high_period = hight_period - hw->scl_high_period.period;
}
/**
* @brief Clear I2C interrupt status
*
* @param hw Beginning address of the peripheral registers
* @param mask Interrupt mask needs to be cleared
*
* @return None
*/
static inline void i2c_ll_clr_intsts_mask(i2c_dev_t *hw, uint32_t mask)
{
hw->int_clr.val = mask;
}
/**
* @brief Enable I2C interrupt
*
* @param hw Beginning address of the peripheral registers
* @param mask Interrupt mask needs to be enabled
*
* @return None
*/
static inline void i2c_ll_enable_intr_mask(i2c_dev_t *hw, uint32_t mask)
{
hw->int_ena.val |= mask;
}
/**
* @brief Disable I2C interrupt
*
* @param hw Beginning address of the peripheral registers
* @param mask Interrupt mask needs to be disabled
*
* @return None
*/
static inline void i2c_ll_disable_intr_mask(i2c_dev_t *hw, uint32_t mask)
{
hw->int_ena.val &= (~mask);
}
/**
* @brief Get I2C interrupt status
*
* @param hw Beginning address of the peripheral registers
*
* @return I2C interrupt status
*/
static inline uint32_t i2c_ll_get_intsts_mask(i2c_dev_t *hw)
{
return hw->int_status.val;
}
/**
* @brief Configure I2C memory access mode, FIFO mode or non-FIFO mode
*
* @param hw Beginning address of the peripheral registers
* @param fifo_mode_en Set true to enable FIFO access mode, else, set it false
*
* @return None
*/
static inline void i2c_ll_set_fifo_mode(i2c_dev_t *hw, bool fifo_mode_en)
{
hw->fifo_conf.nonfifo_en = fifo_mode_en ? 0 : 1;
}
/**
* @brief Configure I2C timeout
*
* @param hw Beginning address of the peripheral registers
* @param tout_num The I2C timeout value needs to be set (2^tout in core clock cycle)
*
* @return None
*/
static inline void i2c_ll_set_tout(i2c_dev_t *hw, int tout)
{
hw->timeout.time_out_value = tout;
}
/**
* @brief Configure I2C slave address
*
* @param hw Beginning address of the peripheral registers
* @param slave_addr I2C slave address needs to be set
* @param addr_10bit_en Set true to enable 10-bit slave address mode, set false to enable 7-bit address mode
*
* @return None
*/
static inline void i2c_ll_set_slave_addr(i2c_dev_t *hw, uint16_t slave_addr, bool addr_10bit_en)
{
hw->slave_addr.addr = slave_addr;
hw->slave_addr.en_10bit = addr_10bit_en;
}
/**
* @brief Write I2C hardware command register
*
* @param hw Beginning address of the peripheral registers
* @param cmd I2C hardware command
* @param cmd_idx The index of the command register, should be less than 16
*
* @return None
*/
static inline void i2c_ll_write_cmd_reg(i2c_dev_t *hw, i2c_hw_cmd_t cmd, int cmd_idx)
{
hw->command[cmd_idx].val = cmd.val;
}
/**
* @brief Configure I2C start timing
*
* @param hw Beginning address of the peripheral registers
* @param start_setup The start condition setup period (in core clock cycle)
* @param start_hold The start condition hold period (in core clock cycle)
*
* @return None
*/
static inline void i2c_ll_set_start_timing(i2c_dev_t *hw, int start_setup, int start_hold)
{
hw->scl_rstart_setup.time = start_setup;
hw->scl_start_hold.time = start_hold - 1;
}
/**
* @brief Configure I2C stop timing
*
* @param hw Beginning address of the peripheral registers
* @param stop_setup The stop condition setup period (in core clock cycle)
* @param stop_hold The stop condition hold period (in core clock cycle)
*
* @return None
*/
static inline void i2c_ll_set_stop_timing(i2c_dev_t *hw, int stop_setup, int stop_hold)
{
hw->scl_stop_setup.time = stop_setup;
hw->scl_stop_hold.time = stop_hold;
}
/**
* @brief Configure I2C stop timing
*
* @param hw Beginning address of the peripheral registers
* @param sda_sample The SDA sample time (in core clock cycle)
* @param sda_hold The SDA hold time (in core clock cycle)
*
* @return None
*/
static inline void i2c_ll_set_sda_timing(i2c_dev_t *hw, int sda_sample, int sda_hold)
{
hw->sda_hold.time = sda_hold;
hw->sda_sample.time = sda_sample;
}
/**
* @brief Set I2C txFIFO empty threshold
*
* @param hw Beginning address of the peripheral registers
* @param empty_thr The txFIFO empty threshold
*
* @return None
*/
static inline void i2c_ll_set_txfifo_empty_thr(i2c_dev_t *hw, uint8_t empty_thr)
{
hw->fifo_conf.tx_fifo_wm_thrhd = empty_thr;
}
/**
* @brief Set I2C rxFIFO full threshold
*
* @param hw Beginning address of the peripheral registers
* @param full_thr The rxFIFO full threshold
*
* @return None
*/
static inline void i2c_ll_set_rxfifo_full_thr(i2c_dev_t *hw, uint8_t full_thr)
{
hw->fifo_conf.rx_fifo_wm_thrhd = full_thr;
}
/**
* @brief Set the I2C data mode, LSB or MSB
*
* @param hw Beginning address of the peripheral registers
* @param tx_mode Tx data bit mode
* @param rx_mode Rx data bit mode
*
* @return None
*/
static inline void i2c_ll_set_data_mode(i2c_dev_t *hw, i2c_trans_mode_t tx_mode, i2c_trans_mode_t rx_mode)
{
hw->ctr.tx_lsb_first = tx_mode;
hw->ctr.rx_lsb_first = rx_mode;
}
/**
* @brief Get the I2C data mode
*
* @param hw Beginning address of the peripheral registers
* @param tx_mode Pointer to accept the received bytes mode
* @param rx_mode Pointer to accept the sended bytes mode
*
* @return None
*/
static inline void i2c_ll_get_data_mode(i2c_dev_t *hw, i2c_trans_mode_t *tx_mode, i2c_trans_mode_t *rx_mode)
{
*tx_mode = hw->ctr.tx_lsb_first;
*rx_mode = hw->ctr.rx_lsb_first;
}
/**
* @brief Get I2C sda timing configuration
*
* @param hw Beginning address of the peripheral registers
* @param sda_sample Pointer to accept the SDA sample timing configuration
* @param sda_hold Pointer to accept the SDA hold timing configuration
*
* @return None
*/
static inline void i2c_ll_get_sda_timing(i2c_dev_t *hw, int *sda_sample, int *sda_hold)
{
*sda_hold = hw->sda_hold.time;
*sda_sample = hw->sda_sample.time;
}
/**
* @brief Get the I2C hardware version
*
* @param hw Beginning address of the peripheral registers
*
* @return The I2C hardware version
*/
static inline uint32_t i2c_ll_get_hw_version(i2c_dev_t *hw)
{
return hw->date;
}
/**
* @brief Check if the I2C bus is busy
*
* @param hw Beginning address of the peripheral registers
*
* @return True if I2C state machine is busy, else false will be returned
*/
static inline bool i2c_ll_is_bus_busy(i2c_dev_t *hw)
{
return hw->sr.bus_busy;
}
/**
* @brief Check if I2C is master mode
*
* @param hw Beginning address of the peripheral registers
*
* @return True if I2C is master mode, else false will be returned
*/
static inline bool i2c_ll_is_master_mode(i2c_dev_t *hw)
{
return hw->ctr.ms_mode;
}
/**
* @brief Get the rxFIFO readable length
*
* @param hw Beginning address of the peripheral registers
*
* @return RxFIFO readable length
*/
static inline uint32_t i2c_ll_get_rxfifo_cnt(i2c_dev_t *hw)
{
return hw->sr.rx_fifo_cnt;
}
/**
* @brief Get I2C txFIFO writable length
*
* @param hw Beginning address of the peripheral registers
*
* @return TxFIFO writable length
*/
static inline uint32_t i2c_ll_get_txfifo_len(i2c_dev_t *hw)
{
return SOC_I2C_FIFO_LEN - hw->sr.tx_fifo_cnt;
}
/**
* @brief Get I2C timeout configuration
*
* @param hw Beginning address of the peripheral registers
*
* @return The I2C timeout value
*/
static inline uint32_t i2c_ll_get_tout(i2c_dev_t *hw)
{
return hw->timeout.time_out_value;
}
/**
* @brief Start I2C transfer
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_trans_start(i2c_dev_t *hw)
{
hw->ctr.trans_start = 1;
}
/**
* @brief Get I2C start timing configuration
*
* @param hw Beginning address of the peripheral registers
* @param setup_time Pointer to accept the start condition setup period
* @param hold_time Pointer to accept the start condition hold period
*
* @return None
*/
static inline void i2c_ll_get_start_timing(i2c_dev_t *hw, int *setup_time, int *hold_time)
{
*setup_time = hw->scl_rstart_setup.time;
*hold_time = hw->scl_start_hold.time + 1;
}
/**
* @brief Get I2C stop timing configuration
*
* @param hw Beginning address of the peripheral registers
* @param setup_time Pointer to accept the stop condition setup period
* @param hold_time Pointer to accept the stop condition hold period
*
* @return None
*/
static inline void i2c_ll_get_stop_timing(i2c_dev_t *hw, int *setup_time, int *hold_time)
{
*setup_time = hw->scl_stop_setup.time;
*hold_time = hw->scl_stop_hold.time;
}
/**
* @brief Get I2C SCL timing configuration
*
* @param hw Beginning address of the peripheral registers
* @param high_period Pointer to accept the SCL high period
* @param low_period Pointer to accept the SCL low period
*
* @return None
*/
static inline void i2c_ll_get_scl_timing(i2c_dev_t *hw, int *high_period, int *low_period)
{
*high_period = hw->scl_high_period.period + hw->scl_high_period.scl_wait_high_period;
*low_period = hw->scl_low_period.period + 1;
}
/**
* @brief Write the I2C hardware txFIFO
*
* @param hw Beginning address of the peripheral registers
* @param ptr Pointer to data buffer
* @param len Amount of data needs to be writen
*
* @return None.
*/
static inline void i2c_ll_write_txfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
{
for (int i = 0; i< len; i++) {
hw->fifo_data.data = ptr[i];
}
}
/**
* @brief Read the I2C hardware rxFIFO
*
* @param hw Beginning address of the peripheral registers
* @param ptr Pointer to data buffer
* @param len Amount of data needs read
*
* @return None
*/
static inline void i2c_ll_read_rxfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
{
for(int i = 0; i < len; i++) {
ptr[i] = hw->fifo_data.data;
}
}
/**
* @brief Configure I2C hardware filter
*
* @param hw Beginning address of the peripheral registers
* @param filter_num If the glitch period on the line is less than this value, it can be filtered out
* If `filter_num == 0`, the filter will be disabled
*
* @return None
*/
static inline void i2c_ll_set_filter(i2c_dev_t *hw, uint8_t filter_num)
{
if (filter_num > 0) {
hw->filter_cfg.scl_thres = filter_num;
hw->filter_cfg.sda_thres = filter_num;
hw->filter_cfg.scl_en = 1;
hw->filter_cfg.sda_en = 1;
} else {
hw->filter_cfg.scl_en = 0;
hw->filter_cfg.sda_en = 0;
}
}
/**
* @brief Get I2C hardware filter configuration
*
* @param hw Beginning address of the peripheral registers
*
* @return The hardware filter configuration
*/
static inline uint8_t i2c_ll_get_filter(i2c_dev_t *hw)
{
return hw->filter_cfg.scl_thres;
}
/**
* @brief Enable I2C master TX interrupt
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_master_enable_tx_it(i2c_dev_t *hw)
{
hw->int_clr.val = ~0;
hw->int_ena.val = I2C_LL_MASTER_TX_INT;
}
/**
* @brief Enable I2C master RX interrupt
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_master_enable_rx_it(i2c_dev_t *hw)
{
hw->int_clr.val = ~0;
hw->int_ena.val = I2C_LL_MASTER_RX_INT;
}
/**
* @brief Disable I2C master TX interrupt
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_master_disable_tx_it(i2c_dev_t *hw)
{
hw->int_ena.val &= (~I2C_LL_MASTER_TX_INT);
}
/**
* @brief Disable I2C master RX interrupt
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_master_disable_rx_it(i2c_dev_t *hw)
{
hw->int_ena.val &= (~I2C_LL_MASTER_RX_INT);
}
/**
* @brief Clear I2C master TX interrupt status register
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_master_clr_tx_it(i2c_dev_t *hw)
{
hw->int_clr.val = I2C_LL_MASTER_TX_INT;
}
/**
* @brief Clear I2C master RX interrupt status register
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_master_clr_rx_it(i2c_dev_t *hw)
{
hw->int_clr.val = I2C_LL_MASTER_RX_INT;
}
/**
* @brief
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_slave_enable_tx_it(i2c_dev_t *hw)
{
hw->int_ena.val |= I2C_LL_SLAVE_TX_INT;
}
/**
* @brief Enable I2C slave RX interrupt
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_slave_enable_rx_it(i2c_dev_t *hw)
{
hw->int_ena.val |= I2C_LL_SLAVE_RX_INT;
}
/**
* @brief Disable I2C slave TX interrupt
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_slave_disable_tx_it(i2c_dev_t *hw)
{
hw->int_ena.val &= (~I2C_LL_SLAVE_TX_INT);
}
/**
* @brief Disable I2C slave RX interrupt
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_slave_disable_rx_it(i2c_dev_t *hw)
{
hw->int_ena.val &= (~I2C_LL_SLAVE_RX_INT);
}
/**
* @brief Clear I2C slave TX interrupt status register
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_slave_clr_tx_it(i2c_dev_t *hw)
{
hw->int_clr.val = I2C_LL_SLAVE_TX_INT;
}
/**
* @brief Clear I2C slave RX interrupt status register.
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_slave_clr_rx_it(i2c_dev_t *hw)
{
hw->int_clr.val = I2C_LL_SLAVE_RX_INT;
}
/**
* @brief Reste I2C master FSM. When the master FSM is stuck, call this function to reset the FSM
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_master_fsm_rst(i2c_dev_t *hw)
{
hw->ctr.fsm_rst = 1;
}
/**
* @brief Clear I2C bus, when the slave is stuck in a deadlock and keeps pulling the bus low,
* master can controls the SCL bus to generate 9 CLKs.
*
* Note: The master cannot detect if deadlock happens, but when the scl_st_to interrupt is generated, a deadlock may occur.
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_master_clr_bus(i2c_dev_t *hw)
{
hw->scl_sp_conf.scl_rst_slv_num = 9;
hw->scl_sp_conf.scl_rst_slv_en = 0;
hw->ctr.conf_upgate = 1;
hw->scl_sp_conf.scl_rst_slv_en = 1;
}
/**
* @brief Set I2C source clock
*
* @param hw Beginning address of the peripheral registers
* @param src_clk Source clock of the I2C
*
* @return None
*/
static inline void i2c_ll_set_source_clk(i2c_dev_t *hw, i2c_sclk_t src_clk)
{
// rtc_clk needs to switch on.
if (src_clk == I2C_SCLK_RTC) {
SET_PERI_REG_MASK(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_DIG_CLK8M_EN_M);
esp_rom_delay_us(DELAY_RTC_CLK_SWITCH);
}
// src_clk : (1) for RTC_CLK, (0) for XTAL
hw->clk_conf.sclk_sel = (src_clk == I2C_SCLK_RTC) ? 1 : 0;
}
/**
* @brief Get I2C master interrupt event
*
* @param hw Beginning address of the peripheral registers
* @param event Pointer to accept the interrupt event
*
* @return None
*/
static inline void i2c_ll_master_get_event(i2c_dev_t *hw, i2c_intr_event_t *event)
{
typeof(hw->int_status) int_sts = hw->int_status;
if (int_sts.arbitration_lost) {
*event = I2C_INTR_EVENT_ARBIT_LOST;
} else if (int_sts.nack) {
*event = I2C_INTR_EVENT_NACK;
} else if (int_sts.time_out) {
*event = I2C_INTR_EVENT_TOUT;
} else if (int_sts.end_detect) {
*event = I2C_INTR_EVENT_END_DET;
} else if (int_sts.trans_complete) {
*event = I2C_INTR_EVENT_TRANS_DONE;
} else {
*event = I2C_INTR_EVENT_ERR;
}
}
/**
* @brief Get I2C slave interrupt event
*
* @param hw Beginning address of the peripheral registers
* @param event Pointer to accept the interrupt event
*
* @return None
*/
static inline void i2c_ll_slave_get_event(i2c_dev_t *hw, i2c_intr_event_t *event)
{
typeof(hw->int_status) int_sts = hw->int_status;
if (int_sts.tx_fifo_wm) {
*event = I2C_INTR_EVENT_TXFIFO_EMPTY;
} else if (int_sts.trans_complete) {
*event = I2C_INTR_EVENT_TRANS_DONE;
} else if (int_sts.rx_fifo_wm) {
*event = I2C_INTR_EVENT_RXFIFO_FULL;
} else {
*event = I2C_INTR_EVENT_ERR;
}
}
/**
* @brief Init I2C master
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_master_init(i2c_dev_t *hw)
{
typeof(hw->ctr) ctrl_reg;
ctrl_reg.val = 0;
ctrl_reg.ms_mode = 1;
ctrl_reg.clk_en = 1;
ctrl_reg.sda_force_out = 1;
ctrl_reg.scl_force_out = 1;
hw->ctr.val = ctrl_reg.val;
}
/**
* @brief Init I2C slave
*
* @param hw Beginning address of the peripheral registers
*
* @return None
*/
static inline void i2c_ll_slave_init(i2c_dev_t *hw)
{
typeof(hw->ctr) ctrl_reg;
ctrl_reg.val = 0;
ctrl_reg.sda_force_out = 1;
ctrl_reg.scl_force_out = 1;
hw->ctr.val = ctrl_reg.val;
hw->ctr.slv_tx_auto_start_en = 1;
hw->fifo_conf.fifo_addr_cfg_en = 0;
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,912 @@
// Copyright 2015-2020 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
/*******************************************************************************
* NOTICE
* The hal is not public api, don't use in application code.
* See readme.md in soc/include/hal/readme.md
******************************************************************************/
// The LL layer for ESP32-S3 I2S register operations
#pragma once
#include <stdbool.h>
#include <stdlib.h>
#include "soc/i2s_periph.h"
#include "hal/i2s_types.h"
#ifdef __cplusplus
extern "C" {
#endif
// Get I2S hardware instance with giving i2s num
#define I2S_LL_GET_HW(num) (((num) == 0) ? (&I2S0) : NULL)
#define I2S_INTR_IN_SUC_EOF BIT(9)
#define I2S_INTR_OUT_EOF BIT(12)
#define I2S_INTR_IN_DSCR_ERR BIT(13)
#define I2S_INTR_OUT_DSCR_ERR BIT(14)
#define I2S_INTR_MAX (0xFFFFFFFF)
/**
* @brief Reset rx fifo
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_reset_rx_fifo(i2s_dev_t *hw)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Reset tx fifo
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_reset_tx_fifo(i2s_dev_t *hw)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Enable rx interrupt
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_enable_rx_intr(i2s_dev_t *hw)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Disable rx interrupt
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_disable_rx_intr(i2s_dev_t *hw)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Disable tx interrupt
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_disable_tx_intr(i2s_dev_t *hw)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Enable tx interrupt
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_enable_tx_intr(i2s_dev_t *hw)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Reset dma in
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_reset_dma_in(i2s_dev_t *hw)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Reset dma out
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_reset_dma_out(i2s_dev_t *hw)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Reset tx
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_reset_tx(i2s_dev_t *hw)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Reset rx
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_reset_rx(i2s_dev_t *hw)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Start out link
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_start_out_link(i2s_dev_t *hw)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Start tx
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_start_tx(i2s_dev_t *hw)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Start in link
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_start_in_link(i2s_dev_t *hw)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Start rx
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_start_rx(i2s_dev_t *hw)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Stop out link
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_stop_out_link(i2s_dev_t *hw)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Stop tx
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_stop_tx(i2s_dev_t *hw)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Stop in link
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_stop_in_link(i2s_dev_t *hw)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Stop rx
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_stop_rx(i2s_dev_t *hw)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Enable dma
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_enable_dma(i2s_dev_t *hw)
{
abort(); // TODO ESP32-C3 IDF-2098
// //Enable and configure DMA
// typeof(hw->lc_conf) lc_conf;
// lc_conf.val = 0;
// lc_conf.out_eof_mode = 1;
}
/**
* @brief Get I2S interrupt status
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to get interrupt status
*/
static inline void i2s_ll_get_intr_status(i2s_dev_t *hw, uint32_t *val)
{
abort(); // TODO ESP32-C3 IDF-2098
// *val = hw->int_st.val;
}
/**
* @brief Clear I2S interrupt status
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to clear interrupt status
*/
static inline void i2s_ll_clear_intr_status(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Get I2S out eof des address
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to get out eof des address
*/
static inline void i2s_ll_get_out_eof_des_addr(i2s_dev_t *hw, uint32_t *val)
{
abort(); // TODO ESP32-C3 IDF-2098
// *val = hw->out_eof_des_addr;
}
/**
* @brief Get I2S in eof des address
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to get in eof des address
*/
static inline void i2s_ll_get_in_eof_des_addr(i2s_dev_t *hw, uint32_t *val)
{
abort(); // TODO ESP32-C3 IDF-2098
// *val = hw->in_eof_des_addr;
}
/**
* @brief Get I2S tx fifo mode
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to get tx fifo mode
*/
static inline void i2s_ll_get_tx_fifo_mod(i2s_dev_t *hw, uint32_t *val)
{
abort(); // TODO ESP32-C3 IDF-2098
// *val = hw->fifo_conf.tx_fifo_mod;
}
/**
* @brief Set I2S tx fifo mode
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set tx fifo mode
*/
static inline void i2s_ll_set_tx_fifo_mod(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Get I2S rx fifo mode
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to get rx fifo mode
*/
static inline void i2s_ll_get_rx_fifo_mod(i2s_dev_t *hw, uint32_t *val)
{
abort(); // TODO ESP32-C3 IDF-2098
// *val = hw->fifo_conf.rx_fifo_mod;
}
/**
* @brief Set I2S rx fifo mode
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set rx fifo mode
*/
static inline void i2s_ll_set_rx_fifo_mod(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S tx chan mode
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set tx chan mode
*/
static inline void i2s_ll_set_tx_chan_mod(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S rx chan mode
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set rx chan mode
*/
static inline void i2s_ll_set_rx_chan_mod(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S out link address
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set out link address
*/
static inline void i2s_ll_set_out_link_addr(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S in link address
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set in link address
*/
static inline void i2s_ll_set_in_link_addr(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S rx eof num
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set rx eof num
*/
static inline void i2s_ll_set_rx_eof_num(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Get I2S tx pdm fp
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to get tx pdm fp
*/
static inline void i2s_ll_get_tx_pdm_fp(i2s_dev_t *hw, uint32_t *val)
{
abort(); // TODO ESP32-C3 IDF-2098
// *val = hw->pdm_freq_conf.tx_pdm_fp;
}
/**
* @brief Get I2S tx pdm fs
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to get tx pdm fs
*/
static inline void i2s_ll_get_tx_pdm_fs(i2s_dev_t *hw, uint32_t *val)
{
abort(); // TODO ESP32-C3 IDF-2098
// *val = hw->pdm_freq_conf.tx_pdm_fs;
}
/**
* @brief Set I2S tx pdm fp
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set tx pdm fp
*/
static inline void i2s_ll_set_tx_pdm_fp(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S tx pdm fs
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set tx pdm fs
*/
static inline void i2s_ll_set_tx_pdm_fs(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Get I2S rx sinc dsr 16 en
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to get rx sinc dsr 16 en
*/
static inline void i2s_ll_get_rx_sinc_dsr_16_en(i2s_dev_t *hw, bool *val)
{
abort(); // TODO ESP32-C3 IDF-2098
// *val = hw->pdm_conf.rx_sinc_dsr_16_en;
}
/**
* @brief Set I2S clkm div num
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set clkm div num
*/
static inline void i2s_ll_set_clkm_div_num(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S clkm div b
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set clkm div b
*/
static inline void i2s_ll_set_clkm_div_b(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S clkm div a
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set clkm div a
*/
static inline void i2s_ll_set_clkm_div_a(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S tx bck div num
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set tx bck div num
*/
static inline void i2s_ll_set_tx_bck_div_num(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S rx bck div num
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set rx bck div num
*/
static inline void i2s_ll_set_rx_bck_div_num(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S clk sel
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set clk sel
*/
static inline void i2s_ll_set_clk_sel(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S tx bits mod
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set tx bits mod
*/
static inline void i2s_ll_set_tx_bits_mod(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S rx bits mod
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set rx bits mod
*/
static inline void i2s_ll_set_rx_bits_mod(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S rx sinc dsr 16 en
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set rx sinc dsr 16 en
*/
static inline void i2s_ll_set_rx_sinc_dsr_16_en(i2s_dev_t *hw, bool val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S dscr en
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set dscr en
*/
static inline void i2s_ll_set_dscr_en(i2s_dev_t *hw, bool val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S lcd en
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set lcd en
*/
static inline void i2s_ll_set_lcd_en(i2s_dev_t *hw, bool val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S camera en
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set camera en
*/
static inline void i2s_ll_set_camera_en(i2s_dev_t *hw, bool val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S pcm2pdm conv en
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set pcm2pdm conv en
*/
static inline void i2s_ll_set_pcm2pdm_conv_en(i2s_dev_t *hw, bool val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S TX to MSB Alignment Standard
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_set_tx_format_msb_align(i2s_dev_t *hw)
{
}
static inline void i2s_ll_set_rx_format_msb_align(i2s_dev_t *hw)
{
}
/**
* @brief Set I2S TX to PCM long standard
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_set_tx_pcm_long(i2s_dev_t *hw)
{
}
/**
* @brief Set I2S RX to PCM long standard
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_set_rx_pcm_long(i2s_dev_t *hw)
{
}
/**
* @brief Set I2S RX to PCM short standard
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_set_rx_pcm_short(i2s_dev_t *hw)
{
}
/**
* @brief Set I2S RX to philip standard
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_set_rx_format_philip(i2s_dev_t *hw)
{
}
/**
* @brief Set I2S TX to PCM short standard
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_set_tx_pcm_short(i2s_dev_t *hw)
{
}
/**
* @brief Set I2S TX to philip standard
*
* @param hw Peripheral I2S hardware instance address.
*/
static inline void i2s_ll_set_tx_format_philip(i2s_dev_t *hw)
{
}
/**
* @brief Set I2S pdm2pcm conv en
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set pdm2pcm conv en
*/
static inline void i2s_ll_set_pdm2pcm_conv_en(i2s_dev_t *hw, bool val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S rx pdm en
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set rx pdm en
*/
static inline void i2s_ll_set_rx_pdm_en(i2s_dev_t *hw, bool val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S tx pdm en
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set tx pdm en
*/
static inline void i2s_ll_set_tx_pdm_en(i2s_dev_t *hw, bool val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S tx fifo mod force en
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set tx fifo mod force en
*/
static inline void i2s_ll_set_tx_fifo_mod_force_en(i2s_dev_t *hw, bool val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S rx fifo mod force en
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set rx fifo mod force en
*/
static inline void i2s_ll_set_rx_fifo_mod_force_en(i2s_dev_t *hw, bool val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S tx right first
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set tx right first
*/
static inline void i2s_ll_set_tx_right_first(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S rx right first
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set rx right first
*/
static inline void i2s_ll_set_rx_right_first(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S tx slave mod
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set tx slave mod
*/
static inline void i2s_ll_set_tx_slave_mod(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S rx slave mod
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set rx slave mod
*/
static inline void i2s_ll_set_rx_slave_mod(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Get I2S tx msb right
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to get tx msb right
*/
static inline void i2s_ll_get_tx_msb_right(i2s_dev_t *hw, uint32_t *val)
{
abort(); // TODO ESP32-C3 IDF-2098
// *val = hw->conf.tx_msb_right;
}
/**
* @brief Get I2S rx msb right
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to get rx msb right
*/
static inline void i2s_ll_get_rx_msb_right(i2s_dev_t *hw, uint32_t *val)
{
abort(); // TODO ESP32-C3 IDF-2098
// *val = hw->conf.rx_msb_right;
}
/**
* @brief Set I2S tx msb right
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set tx msb right
*/
static inline void i2s_ll_set_tx_msb_right(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S rx msb right
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set rx msb right
*/
static inline void i2s_ll_set_rx_msb_right(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S tx mono
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set tx mono
*/
static inline void i2s_ll_set_tx_mono(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S rx mono
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set rx mono
*/
static inline void i2s_ll_set_rx_mono(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S tx sinc osr2
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set tx sinc osr2
*/
static inline void i2s_ll_set_tx_sinc_osr2(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
/**
* @brief Set I2S sig loopback
*
* @param hw Peripheral I2S hardware instance address.
* @param val value to set sig loopback
*/
static inline void i2s_ll_set_sig_loopback(i2s_dev_t *hw, uint32_t val)
{
abort(); // TODO ESP32-C3 IDF-2098
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,132 @@
// 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_caps.h"
#include "soc/soc.h"
#include "soc/interrupt_core0_reg.h"
#include "riscv/interrupt.h"
#include "riscv/csr.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief enable interrupts specified by the mask
*
* @param mask bitmask of interrupts that needs to be enabled
*/
static inline void intr_cntrl_ll_enable_interrupts(uint32_t mask)
{
unsigned old_mstatus = RV_CLEAR_CSR(mstatus, MSTATUS_MIE);
esprv_intc_int_enable(mask);
RV_SET_CSR(mstatus, old_mstatus & MSTATUS_MIE);
}
/**
* @brief disable interrupts specified by the mask
*
* @param mask bitmask of interrupts that needs to be disabled
*/
static inline void intr_cntrl_ll_disable_interrupts(uint32_t mask)
{
unsigned old_mstatus = RV_CLEAR_CSR(mstatus, MSTATUS_MIE);
esprv_intc_int_disable(mask);
RV_SET_CSR(mstatus, old_mstatus & MSTATUS_MIE);
}
/**
* @brief Read the current interrupt mask of the CPU running this code.
*
* @return The current interrupt bitmask.
*/
static inline uint32_t intr_cntrl_ll_read_interrupt_mask(void)
{
return REG_READ(INTERRUPT_CORE0_CPU_INT_ENABLE_REG);
}
/**
* @brief checks if given interrupt number has a valid handler
*
* @param intr interrupt number ranged from 0 to 31
* @param cpu cpu number ranged betweeen 0 to SOC_CPU_CORES_NUM - 1
* @return true for valid handler, false otherwise
*/
static inline bool intr_cntrl_ll_has_handler(uint8_t intr, uint8_t cpu)
{
return intr_handler_get(intr);
}
/**
* @brief sets interrupt handler and optional argument of a given interrupt number
*
* @param intr interrupt number ranged from 0 to 31
* @param handler handler invoked when an interrupt occurs
* @param arg optional argument to pass to the handler
*/
static inline void intr_cntrl_ll_set_int_handler(uint8_t intr, interrupt_handler_t handler, void *arg)
{
intr_handler_set(intr, (void *)handler, arg);
}
/**
* @brief Gets argument passed to handler of a given interrupt number
*
* @param intr interrupt number ranged from 0 to 31
*
* @return argument used by handler of passed interrupt number
*/
static inline void *intr_cntrl_ll_get_int_handler_arg(uint8_t intr)
{
return intr_handler_get_arg(intr);
}
/**
* @brief Acknowledge an edge-trigger interrupt by clearing its pending flag
*
* @param intr interrupt number ranged from 0 to 31
*/
static inline void intr_cntrl_ll_edge_int_acknowledge(int intr)
{
REG_SET_BIT(INTERRUPT_CORE0_CPU_INT_CLEAR_REG, intr);
}
/**
* @brief Sets the interrupt level int the interrupt controller.
*
* @param interrupt_number Interrupt number 0 to 31
* @param level priority between 1 (lowest) to 7 (highest)
*/
static inline void intr_cntrl_ll_set_int_level(int intr, int level)
{
esprv_intc_int_set_priority(intr, level);
}
/**
* @brief Set the type of an interrupt in the controller.
*
* @param interrupt_number Interrupt number 0 to 31
* @param type interrupt type as edge or level triggered
*/
static inline void intr_cntrl_ll_set_int_type(int intr, int_type_t type)
{
esprv_intc_int_set_type(BIT(intr), type);
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,518 @@
// 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.
// The LL layer for LEDC register operations.
// Note that most of the register operations in this layer are non-atomic operations.
#pragma once
#include "hal/ledc_types.h"
#include "soc/ledc_periph.h"
#ifdef __cplusplus
extern "C" {
#endif
#define LEDC_LL_GET_HW() &LEDC
/**
* @brief Set LEDC low speed timer clock
*
* @param hw Beginning address of the peripheral registers
* @param slow_clk_sel LEDC low speed timer clock source
*
* @return None
*/
static inline void ledc_ll_set_slow_clk_sel(ledc_dev_t *hw, ledc_slow_clk_sel_t slow_clk_sel)
{
uint32_t clk_sel_val = 0;
if (slow_clk_sel == LEDC_SLOW_CLK_APB) {
clk_sel_val = 1;
} else if (slow_clk_sel == LEDC_SLOW_CLK_RTC8M) {
clk_sel_val = 2;
} else if (slow_clk_sel == LEDC_SLOW_CLK_XTAL) {
clk_sel_val = 3;
}
hw->conf.apb_clk_sel = clk_sel_val;
}
/**
* @brief Get LEDC low speed timer clock
*
* @param hw Beginning address of the peripheral registers
* @param slow_clk_sel LEDC low speed timer clock source
*
* @return None
*/
static inline void ledc_ll_get_slow_clk_sel(ledc_dev_t *hw, ledc_slow_clk_sel_t *slow_clk_sel)
{
uint32_t clk_sel_val = hw->conf.apb_clk_sel;
if (clk_sel_val == 1) {
*slow_clk_sel = LEDC_SLOW_CLK_APB;
} else if (clk_sel_val == 2) {
*slow_clk_sel = LEDC_SLOW_CLK_RTC8M;
} else if (clk_sel_val == 3) {
*slow_clk_sel = LEDC_SLOW_CLK_XTAL;
}
}
/**
* @brief Update LEDC low speed timer
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param timer_sel LEDC timer index (0-3), select from ledc_timer_t
*
* @return None
*/
static inline void ledc_ll_ls_timer_update(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_timer_t timer_sel)
{
hw->timer_group[speed_mode].timer[timer_sel].conf.low_speed_update = 1;
}
/**
* @brief Reset LEDC timer
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param timer_sel LEDC timer index (0-3), select from ledc_timer_t
*
* @return None
*/
static inline void ledc_ll_timer_rst(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_timer_t timer_sel)
{
hw->timer_group[speed_mode].timer[timer_sel].conf.rst = 1;
hw->timer_group[speed_mode].timer[timer_sel].conf.rst = 0;
}
/**
* @brief Pause LEDC timer
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param timer_sel LEDC timer index (0-3), select from ledc_timer_t
*
* @return None
*/
static inline void ledc_ll_timer_pause(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_timer_t timer_sel)
{
hw->timer_group[speed_mode].timer[timer_sel].conf.pause = 1;
}
/**
* @brief Resume LEDC timer
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param timer_sel LEDC timer index (0-3), select from ledc_timer_t
*
* @return None
*/
static inline void ledc_ll_timer_resume(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_timer_t timer_sel)
{
hw->timer_group[speed_mode].timer[timer_sel].conf.pause = 0;
}
/**
* @brief Set LEDC timer clock divider
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param timer_sel LEDC timer index (0-3), select from ledc_timer_t
* @param clock_divider Timer clock divide value, the timer clock is divided from the selected clock source
*
* @return None
*/
static inline void ledc_ll_set_clock_divider(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_timer_t timer_sel, uint32_t clock_divider)
{
hw->timer_group[speed_mode].timer[timer_sel].conf.clock_divider = clock_divider;
}
/**
* @brief Get LEDC timer clock divider
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param timer_sel LEDC timer index (0-3), select from ledc_timer_t
* @param clock_divider Timer clock divide value, the timer clock is divided from the selected clock source
*
* @return None
*/
static inline void ledc_ll_get_clock_divider(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_timer_t timer_sel, uint32_t *clock_divider)
{
*clock_divider = hw->timer_group[speed_mode].timer[timer_sel].conf.clock_divider;
}
/**
* @brief Set LEDC timer clock source
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param timer_sel LEDC timer index (0-3), select from ledc_timer_t
* @param clk_src Timer clock source
*
* @return None
*/
static inline void ledc_ll_set_clock_source(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_timer_t timer_sel, ledc_clk_src_t clk_src)
{
if (clk_src == LEDC_REF_TICK) {
//REF_TICK can only be used when APB is selected.
hw->timer_group[speed_mode].timer[timer_sel].conf.tick_sel = 1;
hw->conf.apb_clk_sel = 1;
} else {
hw->timer_group[speed_mode].timer[timer_sel].conf.tick_sel = 0;
}
}
/**
* @brief Get LEDC timer clock source
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param timer_sel LEDC timer index (0-3), select from ledc_timer_t
* @param clk_src Pointer to accept the timer clock source
*
* @return None
*/
static inline void ledc_ll_get_clock_source(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_timer_t timer_sel, ledc_clk_src_t *clk_src)
{
if (hw->timer_group[speed_mode].timer[timer_sel].conf.tick_sel == 1) {
*clk_src = LEDC_REF_TICK;
} else {
*clk_src = LEDC_APB_CLK;
}
}
/**
* @brief Set LEDC duty resolution
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param timer_sel LEDC timer index (0-3), select from ledc_timer_t
* @param duty_resolution Resolution of duty setting in number of bits. The range of duty values is [0, (2**duty_resolution)]
*
* @return None
*/
static inline void ledc_ll_set_duty_resolution(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_timer_t timer_sel, uint32_t duty_resolution)
{
hw->timer_group[speed_mode].timer[timer_sel].conf.duty_resolution = duty_resolution;
}
/**
* @brief Get LEDC duty resolution
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param timer_sel LEDC timer index (0-3), select from ledc_timer_t
* @param duty_resolution Pointer to accept the resolution of duty setting in number of bits.
*
* @return None
*/
static inline void ledc_ll_get_duty_resolution(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_timer_t timer_sel, uint32_t *duty_resolution)
{
*duty_resolution = hw->timer_group[speed_mode].timer[timer_sel].conf.duty_resolution;
}
/**
* @brief Update channel configure when select low speed mode
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param channel_num LEDC channel index (0-7), select from ledc_channel_t
*
* @return None
*/
static inline void ledc_ll_ls_channel_update(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_channel_t channel_num)
{
hw->channel_group[speed_mode].channel[channel_num].conf0.low_speed_update = 1;
}
/**
* @brief Get LEDC max duty
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param channel_num LEDC channel index (0-7), select from ledc_channel_t
* @param max_duty Pointer to accept the max duty
*
* @return None
*/
static inline void ledc_ll_get_max_duty(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_channel_t channel_num, uint32_t *max_duty)
{
uint32_t timer_sel = hw->channel_group[speed_mode].channel[channel_num].conf0.timer_sel;
*max_duty = (1 << (LEDC.timer_group[speed_mode].timer[timer_sel].conf.duty_resolution));
}
/**
* @brief Set LEDC hpoint value
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param channel_num LEDC channel index (0-7), select from ledc_channel_t
* @param hpoint_val LEDC hpoint value(max: 0xfffff)
*
* @return None
*/
static inline void ledc_ll_set_hpoint(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_channel_t channel_num, uint32_t hpoint_val)
{
hw->channel_group[speed_mode].channel[channel_num].hpoint.hpoint = hpoint_val;
}
/**
* @brief Get LEDC hpoint value
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param channel_num LEDC channel index (0-7), select from ledc_channel_t
* @param hpoint_val Pointer to accept the LEDC hpoint value(max: 0xfffff)
*
* @return None
*/
static inline void ledc_ll_get_hpoint(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_channel_t channel_num, uint32_t *hpoint_val)
{
*hpoint_val = hw->channel_group[speed_mode].channel[channel_num].hpoint.hpoint;
}
/**
* @brief Set LEDC the integer part of duty value
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param channel_num LEDC channel index (0-7), select from ledc_channel_t
* @param duty_val LEDC duty value, the range of duty setting is [0, (2**duty_resolution)]
*
* @return None
*/
static inline void ledc_ll_set_duty_int_part(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_channel_t channel_num, uint32_t duty_val)
{
hw->channel_group[speed_mode].channel[channel_num].duty.duty = duty_val << 4;
}
/**
* @brief Get LEDC duty value
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param channel_num LEDC channel index (0-7), select from ledc_channel_t
* @param duty_val Pointer to accept the LEDC duty value
*
* @return None
*/
static inline void ledc_ll_get_duty(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_channel_t channel_num, uint32_t *duty_val)
{
*duty_val = (hw->channel_group[speed_mode].channel[channel_num].duty_rd.duty_read >> 4);
}
/**
* @brief Set LEDC duty change direction
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param channel_num LEDC channel index (0-7), select from ledc_channel_t
* @param duty_direction LEDC duty change direction, increase or decrease
*
* @return None
*/
static inline void ledc_ll_set_duty_direction(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_channel_t channel_num, ledc_duty_direction_t duty_direction)
{
hw->channel_group[speed_mode].channel[channel_num].conf1.duty_inc = duty_direction;
}
/**
* @brief Get LEDC duty change direction
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param channel_num LEDC channel index (0-7), select from ledc_channel_t
* @param duty_direction Pointer to accept the LEDC duty change direction, increase or decrease
*
* @return None
*/
static inline void ledc_ll_get_duty_direction(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_channel_t channel_num, ledc_duty_direction_t *duty_direction)
{
*duty_direction = hw->channel_group[speed_mode].channel[channel_num].conf1.duty_inc;
}
/**
* @brief Set the number of increased or decreased times
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param channel_num LEDC channel index (0-7), select from ledc_channel_t
* @param duty_num The number of increased or decreased times
*
* @return None
*/
static inline void ledc_ll_set_duty_num(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_channel_t channel_num, uint32_t duty_num)
{
hw->channel_group[speed_mode].channel[channel_num].conf1.duty_num = duty_num;
}
/**
* @brief Set the duty cycles of increase or decrease
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param channel_num LEDC channel index (0-7), select from ledc_channel_t
* @param duty_cycle The duty cycles
*
* @return None
*/
static inline void ledc_ll_set_duty_cycle(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_channel_t channel_num, uint32_t duty_cycle)
{
hw->channel_group[speed_mode].channel[channel_num].conf1.duty_cycle = duty_cycle;
}
/**
* @brief Set the step scale of increase or decrease
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param channel_num LEDC channel index (0-7), select from ledc_channel_t
* @param duty_scale The step scale
*
* @return None
*/
static inline void ledc_ll_set_duty_scale(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_channel_t channel_num, uint32_t duty_scale)
{
hw->channel_group[speed_mode].channel[channel_num].conf1.duty_scale = duty_scale;
}
/**
* @brief Set the output enable
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param channel_num LEDC channel index (0-7), select from ledc_channel_t
* @param sig_out_en The output enable status
*
* @return None
*/
static inline void ledc_ll_set_sig_out_en(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_channel_t channel_num, bool sig_out_en)
{
hw->channel_group[speed_mode].channel[channel_num].conf0.sig_out_en = sig_out_en;
}
/**
* @brief Set the duty start
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param channel_num LEDC channel index (0-7), select from ledc_channel_t
* @param duty_start The duty start
*
* @return None
*/
static inline void ledc_ll_set_duty_start(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_channel_t channel_num, bool duty_start)
{
hw->channel_group[speed_mode].channel[channel_num].conf1.duty_start = duty_start;
}
/**
* @brief Set output idle level
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param channel_num LEDC channel index (0-7), select from ledc_channel_t
* @param idle_level The output idle level
*
* @return None
*/
static inline void ledc_ll_set_idle_level(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_channel_t channel_num, uint32_t idle_level)
{
hw->channel_group[speed_mode].channel[channel_num].conf0.idle_lv = idle_level & 0x1;
}
/**
* @brief Set fade end interrupt enable
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param channel_num LEDC channel index (0-7), select from ledc_channel_t
* @param fade_end_intr_en The fade end interrupt enable status
*
* @return None
*/
static inline void ledc_ll_set_fade_end_intr(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_channel_t channel_num, bool fade_end_intr_en)
{
uint32_t value = hw->int_ena.val;
uint32_t int_en_base = LEDC_DUTY_CHNG_END_LSCH0_INT_ENA_S;
hw->int_ena.val = fade_end_intr_en ? (value | BIT(int_en_base + channel_num)) : (value & (~(BIT(int_en_base + channel_num))));
}
/**
* @brief Get fade end interrupt status
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param channel_num LEDC channel index (0-7), select from ledc_channel_t
* @param intr_status The fade end interrupt status
*
* @return None
*/
static inline void ledc_ll_get_fade_end_intr_status(ledc_dev_t *hw, ledc_mode_t speed_mode, uint32_t *intr_status)
{
uint32_t value = hw->int_st.val;
uint32_t int_en_base = LEDC_DUTY_CHNG_END_LSCH0_INT_ENA_S;
*intr_status = (value >> int_en_base) & 0xff;
}
/**
* @brief Clear fade end interrupt status
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param channel_num LEDC channel index (0-7), select from ledc_channel_t
*
* @return None
*/
static inline void ledc_ll_clear_fade_end_intr_status(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_channel_t channel_num)
{
uint32_t int_en_base = LEDC_DUTY_CHNG_END_LSCH0_INT_ENA_S;
hw->int_clr.val = BIT(int_en_base + channel_num);
}
/**
* @brief Set timer index of the specified channel
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param channel_num LEDC channel index (0-7), select from ledc_channel_t
* @param timer_sel LEDC timer index (0-3), select from ledc_timer_t
*
* @return None
*/
static inline void ledc_ll_bind_channel_timer(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_channel_t channel_num, ledc_timer_t timer_sel)
{
hw->channel_group[speed_mode].channel[channel_num].conf0.timer_sel = timer_sel;
}
/**
* @brief Get timer index of the specified channel
*
* @param hw Beginning address of the peripheral registers
* @param speed_mode LEDC speed_mode, high-speed mode or low-speed mode
* @param channel_num LEDC channel index (0-7), select from ledc_channel_t
* @param timer_sel Pointer to accept the LEDC timer index
*
* @return None
*/
static inline void ledc_ll_get_channel_timer(ledc_dev_t *hw, ledc_mode_t speed_mode, ledc_channel_t channel_num, ledc_timer_t *timer_sel)
{
*timer_sel = hw->channel_group[speed_mode].channel[channel_num].conf0.timer_sel;
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,571 @@
// 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 "soc/sensitive_reg.h"
#include "soc/cache_memory.h"
#ifdef __cplusplus
extern "C" {
#endif
/* ******************************************************************************************************
* *** GLOBALS ***
* NOTE: in this version, all the configurations apply only to WORLD_0
*/
#define IRAM_SRAM_START 0x4037C000
#define DRAM_SRAM_START 0x3FC7C000
/* ICache size is fixed to 16KB on ESP32-C3 */
#ifndef ICACHE_SIZE
#define ICACHE_SIZE 0x4000
#endif
#ifndef I_D_SRAM_SEGMENT_SIZE
#define I_D_SRAM_SEGMENT_SIZE 0x20000
#endif
#define I_D_SPLIT_LINE_SHIFT 0x9
#define I_D_FAULT_ADDR_SHIFT 0x2
static inline void memprot_ll_set_iram0_dram0_split_line_lock(void)
{
REG_WRITE(SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SPLIT_LINE_CONSTRAIN_0_REG, 1);
}
static inline bool memprot_ll_get_iram0_dram0_split_line_lock(void)
{
return REG_READ(SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SPLIT_LINE_CONSTRAIN_0_REG) == 1;
}
static inline void* memprot_ll_get_split_addr_from_reg(uint32_t regval, uint32_t base)
{
return (void*)
(base + ((regval & SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SRAM_SPLITADDR_M)
>> (SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SRAM_SPLITADDR_S - I_D_SPLIT_LINE_SHIFT)));
}
/* ******************************************************************************************************
* *** IRAM0 ***
*/
//16kB (CACHE)
#define IRAM0_SRAM_LEVEL_0_LOW IRAM_SRAM_START //0x40370000
#define IRAM0_SRAM_LEVEL_0_HIGH (IRAM0_SRAM_LEVEL_0_LOW + ICACHE_SIZE - 0x1) //0x4037FFFF
//128kB (LEVEL 1)
#define IRAM0_SRAM_LEVEL_1_LOW (IRAM0_SRAM_LEVEL_0_HIGH + 0x1) //0x40380000
#define IRAM0_SRAM_LEVEL_1_HIGH (IRAM0_SRAM_LEVEL_1_LOW + I_D_SRAM_SEGMENT_SIZE - 0x1) //0x4039FFFF
//128kB (LEVEL 2)
#define IRAM0_SRAM_LEVEL_2_LOW (IRAM0_SRAM_LEVEL_1_HIGH + 0x1) //0x403A0000
#define IRAM0_SRAM_LEVEL_2_HIGH (IRAM0_SRAM_LEVEL_2_LOW + I_D_SRAM_SEGMENT_SIZE - 0x1) //0x403BFFFF
//128kB (LEVEL 3)
#define IRAM0_SRAM_LEVEL_3_LOW (IRAM0_SRAM_LEVEL_2_HIGH + 0x1) //0x403C0000
#define IRAM0_SRAM_LEVEL_3_HIGH (IRAM0_SRAM_LEVEL_3_LOW + I_D_SRAM_SEGMENT_SIZE - 0x1) //0x403DFFFF
//permission bits
#define SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_R 0x1
#define SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_W 0x2
#define SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_F 0x4
static inline uint32_t memprot_ll_iram0_get_intr_source_num(void)
{
return ETS_CORE0_IRAM0_PMS_INTR_SOURCE;
}
///////////////////////////////////
// IRAM0 - SPLIT LINES
///////////////////////////////////
static inline void memprot_ll_set_iram0_split_line(const void *line_addr, uint32_t sensitive_reg)
{
uint32_t addr = (uint32_t)line_addr;
assert( addr >= IRAM0_SRAM_LEVEL_1_LOW && addr <= IRAM0_SRAM_LEVEL_3_HIGH );
uint32_t category[3] = {0};
if (addr <= IRAM0_SRAM_LEVEL_1_HIGH) {
category[0] = 0x2;
category[1] = category[2] = 0x3;
} else if (addr >= IRAM0_SRAM_LEVEL_2_LOW && addr <= IRAM0_SRAM_LEVEL_2_HIGH) {
category[1] = 0x2;
category[2] = 0x3;
} else {
category[2] = 0x2;
}
//NOTE: category & split line address bits are the same for all the areas
uint32_t category_bits =
(category[0] << SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SRAM_CATEGORY_0_S) |
(category[1] << SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SRAM_CATEGORY_1_S) |
(category[2] << SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SRAM_CATEGORY_2_S);
uint32_t conf_addr = ((addr >> I_D_SPLIT_LINE_SHIFT) & SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SRAM_SPLITADDR_V) << SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SRAM_SPLITADDR_S;
uint32_t reg_cfg = conf_addr | category_bits;
REG_WRITE(sensitive_reg, reg_cfg);
}
/* can be both IRAM0/DRAM0 address */
static inline void memprot_ll_set_iram0_split_line_main_I_D(const void *line_addr)
{
memprot_ll_set_iram0_split_line(line_addr, SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SPLIT_LINE_CONSTRAIN_1_REG);
}
static inline void memprot_ll_set_iram0_split_line_I_0(const void *line_addr)
{
memprot_ll_set_iram0_split_line(line_addr, SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SPLIT_LINE_CONSTRAIN_2_REG);
}
static inline void memprot_ll_set_iram0_split_line_I_1(const void *line_addr)
{
memprot_ll_set_iram0_split_line(line_addr, SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SPLIT_LINE_CONSTRAIN_3_REG);
}
static inline void* memprot_ll_get_iram0_split_line_main_I_D(void)
{
return memprot_ll_get_split_addr_from_reg(REG_READ(SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SPLIT_LINE_CONSTRAIN_1_REG), SOC_DIRAM_IRAM_LOW);
}
static inline void* memprot_ll_get_iram0_split_line_I_0(void)
{
return memprot_ll_get_split_addr_from_reg(REG_READ(SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SPLIT_LINE_CONSTRAIN_2_REG), SOC_DIRAM_IRAM_LOW);
}
static inline void* memprot_ll_get_iram0_split_line_I_1(void)
{
return memprot_ll_get_split_addr_from_reg(REG_READ(SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SPLIT_LINE_CONSTRAIN_3_REG), SOC_DIRAM_IRAM_LOW);
}
///////////////////////////////////
// IRAM0 - PMS CONFIGURATION
///////////////////////////////////
// lock
static inline void memprot_ll_iram0_set_pms_lock(void)
{
REG_WRITE(SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_0_REG, 1);
}
static inline bool memprot_ll_iram0_get_pms_lock(void)
{
return REG_READ(SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_0_REG) == 1;
}
// permission settings
static inline uint32_t memprot_ll_iram0_set_permissions(bool r, bool w, bool x)
{
uint32_t permissions = 0;
if ( r ) {
permissions |= SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_R;
}
if ( w ) {
permissions |= SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_W;
}
if ( x ) {
permissions |= SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_F;
}
return permissions;
}
static inline void memprot_ll_iram0_set_pms_area_0(bool r, bool w, bool x)
{
REG_SET_FIELD(SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_2_REG, SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_PMS_0, memprot_ll_iram0_set_permissions(r, w, x));
}
static inline void memprot_ll_iram0_set_pms_area_1(bool r, bool w, bool x)
{
REG_SET_FIELD(SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_2_REG, SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_PMS_1, memprot_ll_iram0_set_permissions(r, w, x));
}
static inline void memprot_ll_iram0_set_pms_area_2(bool r, bool w, bool x)
{
REG_SET_FIELD(SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_2_REG, SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_PMS_2, memprot_ll_iram0_set_permissions(r, w, x));
}
static inline void memprot_ll_iram0_set_pms_area_3(bool r, bool w, bool x)
{
REG_SET_FIELD(SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_2_REG, SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_PMS_3, memprot_ll_iram0_set_permissions(r, w, x));
}
static inline void memprot_ll_iram0_get_permissions(uint32_t perms, bool *r, bool *w, bool *x)
{
*r = perms & SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_R;
*w = perms & SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_W;
*x = perms & SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_F;
}
static inline void memprot_ll_iram0_get_pms_area_0(bool *r, bool *w, bool *x)
{
uint32_t permissions = REG_GET_FIELD(SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_2_REG, SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_PMS_0);
memprot_ll_iram0_get_permissions( permissions, r, w, x);
}
static inline void memprot_ll_iram0_get_pms_area_1(bool *r, bool *w, bool *x)
{
uint32_t permissions = REG_GET_FIELD(SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_2_REG, SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_PMS_1);
memprot_ll_iram0_get_permissions( permissions, r, w, x);
}
static inline void memprot_ll_iram0_get_pms_area_2(bool *r, bool *w, bool *x)
{
uint32_t permissions = REG_GET_FIELD(SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_2_REG, SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_PMS_2);
memprot_ll_iram0_get_permissions( permissions, r, w, x);
}
static inline void memprot_ll_iram0_get_pms_area_3(bool *r, bool *w, bool *x)
{
uint32_t permissions = REG_GET_FIELD(SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_2_REG, SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_PMS_3);
memprot_ll_iram0_get_permissions( permissions, r, w, x);
}
///////////////////////////////////
// IRAM0 - MONITOR
///////////////////////////////////
// lock
static inline void memprot_ll_iram0_set_monitor_lock(void)
{
REG_WRITE(SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_0_REG, 1);
}
static inline bool memprot_ll_iram0_get_monitor_lock(void)
{
return REG_READ(SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_0_REG) == 1;
}
// interrupt enable/clear
static inline void memprot_ll_iram0_set_monitor_en(bool enable)
{
if ( enable ) {
REG_SET_BIT( SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_1_REG, SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_VIOLATE_EN );
} else {
REG_CLR_BIT( SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_1_REG, SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_VIOLATE_EN );
}
}
static inline bool memprot_ll_iram0_get_monitor_en(void)
{
return REG_GET_FIELD( SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_1_REG, SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_VIOLATE_EN ) == 1;
}
static inline void memprot_ll_iram0_clear_monitor_intr(void)
{
REG_SET_BIT( SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_1_REG, SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_VIOLATE_CLR );
}
static inline void memprot_ll_iram0_reset_clear_monitor_intr(void)
{
REG_CLR_BIT( SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_1_REG, SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_VIOLATE_CLR );
}
static inline uint32_t memprot_ll_iram0_get_monitor_enable_register(void)
{
return REG_READ(SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_1_REG);
}
// // permission violation status
static inline uint32_t memprot_ll_iram0_get_monitor_status_intr(void)
{
return REG_GET_FIELD( SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_2_REG, SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_VIOLATE_INTR );
}
static inline uint32_t memprot_ll_iram0_get_monitor_status_fault_wr(void)
{
return REG_GET_FIELD( SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_2_REG, SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_VIOLATE_STATUS_WR );
}
static inline uint32_t memprot_ll_iram0_get_monitor_status_fault_loadstore(void)
{
return REG_GET_FIELD( SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_2_REG, SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_VIOLATE_STATUS_LOADSTORE );
}
static inline uint32_t memprot_ll_iram0_get_monitor_status_fault_world(void)
{
return REG_GET_FIELD( SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_2_REG, SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_VIOLATE_STATUS_WORLD );
}
static inline uint32_t memprot_ll_iram0_get_monitor_status_fault_addr(void)
{
uint32_t addr = REG_GET_FIELD( SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_2_REG, SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_VIOLATE_STATUS_ADDR );
return addr > 0 ? (addr << I_D_FAULT_ADDR_SHIFT) + IRAM0_ADDRESS_LOW : 0;
}
static inline uint32_t memprot_ll_iram0_get_monitor_status_register(void)
{
return REG_READ(SENSITIVE_CORE_0_IRAM0_PMS_MONITOR_2_REG);
}
/* ******************************************************************************************************
* *** DRAM0 ***
*/
//cache not available from DRAM (!)
#define DRAM0_SRAM_LEVEL_0_LOW DRAM_SRAM_START //0x3FC7C000
#define DRAM0_SRAM_LEVEL_0_HIGH (DRAM0_SRAM_LEVEL_0_LOW + ICACHE_SIZE - 0x1) //0x3FC7FFFF
//128kB
#define DRAM0_SRAM_LEVEL_1_LOW (DRAM0_SRAM_LEVEL_0_HIGH + 0x1) //0x3FC80000
#define DRAM0_SRAM_LEVEL_1_HIGH (DRAM0_SRAM_LEVEL_1_LOW + I_D_SRAM_SEGMENT_SIZE - 0x1) //0x3FC9FFFF
//128kB
#define DRAM0_SRAM_LEVEL_2_LOW (DRAM0_SRAM_LEVEL_1_HIGH + 0x1) //0x3FCA0000
#define DRAM0_SRAM_LEVEL_2_HIGH (DRAM0_SRAM_LEVEL_2_LOW + I_D_SRAM_SEGMENT_SIZE - 0x1) //0x3FCBFFFF
//128kB
#define DRAM0_SRAM_LEVEL_3_LOW (DRAM0_SRAM_LEVEL_2_HIGH + 0x1) //0x3FCC0000
#define DRAM0_SRAM_LEVEL_3_HIGH (DRAM0_SRAM_LEVEL_3_LOW + I_D_SRAM_SEGMENT_SIZE - 0x1) //0x3FCDFFFF
#define SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_W 0x2
#define SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_R 0x1
static inline uint32_t memprot_ll_dram0_get_intr_source_num(void)
{
return ETS_CORE0_DRAM0_PMS_INTR_SOURCE;
}
///////////////////////////////////
// DRAM0 - SPLIT LINES
///////////////////////////////////
static inline void memprot_ll_set_dram0_split_line(const void *line_addr, uint32_t sensitive_reg)
{
uint32_t addr = (uint32_t)line_addr;
assert( addr >= DRAM0_SRAM_LEVEL_1_LOW && addr <= DRAM0_SRAM_LEVEL_3_HIGH );
uint32_t category[3] = {0};
if (addr <= DRAM0_SRAM_LEVEL_1_HIGH) {
category[0] = 0x2;
category[1] = category[2] = 0x3;
} else if (addr >= DRAM0_SRAM_LEVEL_2_LOW && addr <= DRAM0_SRAM_LEVEL_2_HIGH) {
category[1] = 0x2;
category[2] = 0x3;
} else {
category[2] = 0x2;
}
//NOTE: line address & category bits, shifts and masks are the same for all the areas
uint32_t category_bits =
(category[0] << SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SRAM_CATEGORY_0_S) |
(category[1] << SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SRAM_CATEGORY_1_S) |
(category[2] << SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SRAM_CATEGORY_2_S);
uint32_t conf_addr = ((addr >> I_D_SPLIT_LINE_SHIFT) & SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SRAM_SPLITADDR_V) << SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SRAM_SPLITADDR_S;
uint32_t reg_cfg = conf_addr | category_bits;
REG_WRITE(sensitive_reg, reg_cfg);
}
static inline void memprot_ll_set_dram0_split_line_D_0(const void *line_addr)
{
memprot_ll_set_dram0_split_line(line_addr, SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SPLIT_LINE_CONSTRAIN_2_REG);
}
static inline void memprot_ll_set_dram0_split_line_D_1(const void *line_addr)
{
memprot_ll_set_dram0_split_line(line_addr, SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SPLIT_LINE_CONSTRAIN_3_REG);
}
static inline void* memprot_ll_get_dram0_split_line_D_0(void)
{
return memprot_ll_get_split_addr_from_reg(REG_READ(SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SPLIT_LINE_CONSTRAIN_2_REG), SOC_DIRAM_DRAM_LOW);
}
static inline void* memprot_ll_get_dram0_split_line_D_1(void)
{
return memprot_ll_get_split_addr_from_reg(REG_READ(SENSITIVE_CORE_X_IRAM0_DRAM0_DMA_SPLIT_LINE_CONSTRAIN_3_REG), SOC_DIRAM_DRAM_LOW);
}
///////////////////////////////////
// DRAM0 - PMS CONFIGURATION
///////////////////////////////////
// lock
static inline void memprot_ll_dram0_set_pms_lock(void)
{
REG_WRITE(SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_0_REG, 1);
}
static inline bool memprot_ll_dram0_get_pms_lock(void)
{
return REG_READ(SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_0_REG) == 1;
}
// permission settings
static inline uint32_t memprot_ll_dram0_set_permissions(bool r, bool w)
{
uint32_t permissions = 0;
if ( r ) {
permissions |= SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_R;
}
if ( w ) {
permissions |= SENSITIVE_CORE_X_IRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_W;
}
return permissions;
}
static inline void memprot_ll_dram0_set_pms_area_0(bool r, bool w)
{
REG_SET_FIELD(SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_1_REG, SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_PMS_0, memprot_ll_dram0_set_permissions(r, w));
}
static inline void memprot_ll_dram0_set_pms_area_1(bool r, bool w)
{
REG_SET_FIELD(SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_1_REG, SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_PMS_1, memprot_ll_dram0_set_permissions(r, w));
}
static inline void memprot_ll_dram0_set_pms_area_2(bool r, bool w)
{
REG_SET_FIELD(SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_1_REG, SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_PMS_2, memprot_ll_dram0_set_permissions(r, w));
}
static inline void memprot_ll_dram0_set_pms_area_3(bool r, bool w)
{
REG_SET_FIELD(SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_1_REG, SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_PMS_3, memprot_ll_dram0_set_permissions(r, w));
}
static inline void memprot_ll_dram0_get_permissions(uint32_t perms, bool *r, bool *w )
{
*r = perms & SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_R;
*w = perms & SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_W;
}
static inline void memprot_ll_dram0_get_pms_area_0(bool *r, bool *w)
{
uint32_t permissions = REG_GET_FIELD(SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_1_REG, SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_PMS_0);
memprot_ll_dram0_get_permissions( permissions, r, w);
}
static inline void memprot_ll_dram0_get_pms_area_1(bool *r, bool *w)
{
uint32_t permissions = REG_GET_FIELD(SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_1_REG, SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_PMS_1);
memprot_ll_dram0_get_permissions( permissions, r, w);
}
static inline void memprot_ll_dram0_get_pms_area_2(bool *r, bool *w)
{
uint32_t permissions = REG_GET_FIELD(SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_1_REG, SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_PMS_2);
memprot_ll_dram0_get_permissions( permissions, r, w);
}
static inline void memprot_ll_dram0_get_pms_area_3(bool *r, bool *w)
{
uint32_t permissions = REG_GET_FIELD(SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_1_REG, SENSITIVE_CORE_X_DRAM0_PMS_CONSTRAIN_SRAM_WORLD_0_PMS_3);
memprot_ll_dram0_get_permissions( permissions, r, w);
}
///////////////////////////////////
// DRAM0 - MONITOR
///////////////////////////////////
// lock
static inline void memprot_ll_dram0_set_monitor_lock(void)
{
REG_WRITE(SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_0_REG, 1);
}
static inline bool memprot_ll_dram0_get_monitor_lock(void)
{
return REG_READ(SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_0_REG) == 1;
}
// interrupt enable/clear
static inline void memprot_ll_dram0_set_monitor_en(bool enable)
{
if ( enable ) {
REG_SET_BIT( SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_1_REG, SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_VIOLATE_EN );
} else {
REG_CLR_BIT( SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_1_REG, SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_VIOLATE_EN );
}
}
static inline bool memprot_ll_dram0_get_monitor_en(void)
{
return REG_GET_BIT( SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_1_REG, SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_VIOLATE_EN ) == 1;
}
static inline void memprot_ll_dram0_clear_monitor_intr(void)
{
REG_SET_BIT( SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_1_REG, SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_VIOLATE_CLR );
}
static inline void memprot_ll_dram0_reset_clear_monitor_intr(void)
{
REG_CLR_BIT( SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_1_REG, SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_VIOLATE_CLR );
}
static inline uint32_t memprot_ll_dram0_get_monitor_enable_register(void)
{
return REG_READ(SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_1_REG);
}
// permission violation status
static inline uint32_t memprot_ll_dram0_get_monitor_status_intr(void)
{
return REG_GET_FIELD( SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_2_REG, SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_VIOLATE_INTR );
}
static inline uint32_t memprot_ll_dram0_get_monitor_status_fault_lock(void)
{
return REG_GET_FIELD( SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_2_REG, SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_VIOLATE_STATUS_LOCK );
}
static inline uint32_t memprot_ll_dram0_get_monitor_status_fault_world(void)
{
return REG_GET_FIELD( SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_2_REG, SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_VIOLATE_STATUS_WORLD );
}
static inline uint32_t memprot_ll_dram0_get_monitor_status_fault_addr(void)
{
uint32_t addr = REG_GET_FIELD( SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_2_REG, SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_VIOLATE_STATUS_ADDR );
return addr > 0 ? (addr << I_D_FAULT_ADDR_SHIFT) + DRAM0_ADDRESS_LOW : 0;
}
static inline uint32_t memprot_ll_dram0_get_monitor_status_fault_wr(void)
{
return REG_GET_FIELD( SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_3_REG, SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_VIOLATE_STATUS_WR );
}
static inline uint32_t memprot_ll_dram0_get_monitor_status_fault_byte_en(void)
{
return REG_GET_FIELD( SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_2_REG, SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_VIOLATE_STATUS_BYTEEN );
}
static inline uint32_t memprot_ll_dram0_get_monitor_status_register_1(void)
{
return REG_READ(SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_2_REG);
}
static inline uint32_t memprot_ll_dram0_get_monitor_status_register_2(void)
{
return REG_READ(SENSITIVE_CORE_0_DRAM0_PMS_MONITOR_3_REG);
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,53 @@
// 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 <stdint.h>
#include "soc/soc_caps.h"
#ifdef __cplusplus
extern "C" {
#endif
/* This LL is currently unused for ESP32-C3 - cleanup is TODO ESP32-C3 IDF-2375 */
static inline uint32_t mpu_ll_id_to_addr(unsigned id)
{
abort();
}
static inline void mpu_ll_set_region_rw(uint32_t addr)
{
abort();
}
static inline void mpu_ll_set_region_rwx(uint32_t addr)
{
abort();
}
static inline void mpu_ll_set_region_x(uint32_t addr)
{
abort();
}
static inline void mpu_ll_set_region_illegal(uint32_t addr)
{
abort();
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,254 @@
// 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.
// The LL layer for Timer Group register operations.
// Note that most of the register operations in this layer are non-atomic operations.
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <stdbool.h>
#include "soc/timer_periph.h"
#include "hal/wdt_types.h"
#include "esp_attr.h"
//Type check wdt_stage_action_t
_Static_assert(WDT_STAGE_ACTION_OFF == TIMG_WDT_STG_SEL_OFF, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_stage_action_t");
_Static_assert(WDT_STAGE_ACTION_INT == TIMG_WDT_STG_SEL_INT, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_stage_action_t");
_Static_assert(WDT_STAGE_ACTION_RESET_CPU == TIMG_WDT_STG_SEL_RESET_CPU, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_stage_action_t");
_Static_assert(WDT_STAGE_ACTION_RESET_SYSTEM == TIMG_WDT_STG_SEL_RESET_SYSTEM, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_stage_action_t");
//Type check wdt_reset_sig_length_t
_Static_assert(WDT_RESET_SIG_LENGTH_100ns == TIMG_WDT_RESET_LENGTH_100_NS, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_reset_sig_length_t");
_Static_assert(WDT_RESET_SIG_LENGTH_200ns == TIMG_WDT_RESET_LENGTH_200_NS, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_reset_sig_length_t");
_Static_assert(WDT_RESET_SIG_LENGTH_300ns == TIMG_WDT_RESET_LENGTH_300_NS, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_reset_sig_length_t");
_Static_assert(WDT_RESET_SIG_LENGTH_400ns == TIMG_WDT_RESET_LENGTH_400_NS, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_reset_sig_length_t");
_Static_assert(WDT_RESET_SIG_LENGTH_500ns == TIMG_WDT_RESET_LENGTH_500_NS, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_reset_sig_length_t");
_Static_assert(WDT_RESET_SIG_LENGTH_800ns == TIMG_WDT_RESET_LENGTH_800_NS, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_reset_sig_length_t");
_Static_assert(WDT_RESET_SIG_LENGTH_1_6us == TIMG_WDT_RESET_LENGTH_1600_NS, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_reset_sig_length_t");
_Static_assert(WDT_RESET_SIG_LENGTH_3_2us == TIMG_WDT_RESET_LENGTH_3200_NS, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_reset_sig_length_t");
/**
* @brief Enable the MWDT
*
* @param hw Start address of the peripheral registers.
*/
FORCE_INLINE_ATTR void mwdt_ll_enable(timg_dev_t *hw)
{
hw->wdt_config0.en = 1;
}
/**
* @brief Disable the MWDT
*
* @param hw Start address of the peripheral registers.
* @note This function does not disable the flashboot mode. Therefore, given that
* the MWDT is disabled using this function, a timeout can still occur
* if the flashboot mode is simultaneously enabled.
*/
FORCE_INLINE_ATTR void mwdt_ll_disable(timg_dev_t *hw)
{
hw->wdt_config0.en = 0;
}
/**
* Check if the MWDT is enabled
*
* @param hw Start address of the peripheral registers.
* @return True if the MWDT is enabled, false otherwise
*/
FORCE_INLINE_ATTR bool mwdt_ll_check_if_enabled(timg_dev_t *hw)
{
return (hw->wdt_config0.en) ? true : false;
}
/**
* @brief Configure a particular stage of the MWDT
*
* @param hw Start address of the peripheral registers.
* @param stage Which stage to configure
* @param timeout Number of timer ticks for the stage to timeout
* @param behavior What action to take when the stage times out
*/
FORCE_INLINE_ATTR void mwdt_ll_config_stage(timg_dev_t *hw, wdt_stage_t stage, uint32_t timeout, wdt_stage_action_t behavior)
{
switch (stage) {
case WDT_STAGE0:
hw->wdt_config0.stg0 = behavior;
hw->wdt_config2 = timeout;
break;
case WDT_STAGE1:
hw->wdt_config0.stg1 = behavior;
hw->wdt_config3 = timeout;
break;
case WDT_STAGE2:
hw->wdt_config0.stg2 = behavior;
hw->wdt_config4 = timeout;
break;
case WDT_STAGE3:
hw->wdt_config0.stg3 = behavior;
hw->wdt_config5 = timeout;
break;
default:
break;
}
//Config registers are updated asynchronously
hw->wdt_config0.conf_update_en = 1;
}
/**
* @brief Disable a particular stage of the MWDT
*
* @param hw Start address of the peripheral registers.
* @param stage Which stage to disable
*/
FORCE_INLINE_ATTR void mwdt_ll_disable_stage(timg_dev_t *hw, uint32_t stage)
{
switch (stage) {
case WDT_STAGE0:
hw->wdt_config0.stg0 = WDT_STAGE_ACTION_OFF;
break;
case WDT_STAGE1:
hw->wdt_config0.stg1 = WDT_STAGE_ACTION_OFF;
break;
case WDT_STAGE2:
hw->wdt_config0.stg2 = WDT_STAGE_ACTION_OFF;
break;
case WDT_STAGE3:
hw->wdt_config0.stg3 = WDT_STAGE_ACTION_OFF;
break;
default:
break;
}
//Config registers are updated asynchronously
hw->wdt_config0.conf_update_en = 1;
}
/**
* @brief Set the length of the CPU reset action
*
* @param hw Start address of the peripheral registers.
* @param length Length of CPU reset signal
*/
FORCE_INLINE_ATTR void mwdt_ll_set_cpu_reset_length(timg_dev_t *hw, wdt_reset_sig_length_t length)
{
hw->wdt_config0.cpu_reset_length = length;
//Config registers are updated asynchronously
hw->wdt_config0.conf_update_en = 1;
}
/**
* @brief Set the length of the system reset action
*
* @param hw Start address of the peripheral registers.
* @param length Length of system reset signal
*/
FORCE_INLINE_ATTR void mwdt_ll_set_sys_reset_length(timg_dev_t *hw, wdt_reset_sig_length_t length)
{
hw->wdt_config0.sys_reset_length = length;
//Config registers are updated asynchronously
hw->wdt_config0.conf_update_en = 1;
}
/**
* @brief Enable/Disable the MWDT flashboot mode.
*
* @param hw Beginning address of the peripheral registers.
* @param enable True to enable WDT flashboot mode, false to disable WDT flashboot mode.
*
* @note Flashboot mode is independent and can trigger a WDT timeout event if the
* WDT's enable bit is set to 0. Flashboot mode for TG0 is automatically enabled
* on flashboot, and should be disabled by software when flashbooting completes.
*/
FORCE_INLINE_ATTR void mwdt_ll_set_flashboot_en(timg_dev_t *hw, bool enable)
{
hw->wdt_config0.flashboot_mod_en = (enable) ? 1 : 0;
//Config registers are updated asynchronously
hw->wdt_config0.conf_update_en = 1;
}
/**
* @brief Set the clock prescaler of the MWDT
*
* @param hw Start address of the peripheral registers.
* @param prescaler Prescaler value between 1 to 65535
*/
FORCE_INLINE_ATTR void mwdt_ll_set_prescaler(timg_dev_t *hw, uint32_t prescaler)
{
hw->wdt_config1.clk_prescale = prescaler;
//Config registers are updated asynchronously
hw->wdt_config0.conf_update_en = 1;
}
/**
* @brief Feed the MWDT
*
* Resets the current timer count and current stage.
*
* @param hw Start address of the peripheral registers.
*/
FORCE_INLINE_ATTR void mwdt_ll_feed(timg_dev_t *hw)
{
hw->wdt_feed = 1;
}
/**
* @brief Enable write protection of the MWDT registers
*
* Locking the MWDT will prevent any of the MWDT's registers from being modified
*
* @param hw Start address of the peripheral registers.
*/
FORCE_INLINE_ATTR void mwdt_ll_write_protect_enable(timg_dev_t *hw)
{
hw->wdt_wprotect = 0;
}
/**
* @brief Disable write protection of the MWDT registers
*
* @param hw Start address of the peripheral registers.
*/
FORCE_INLINE_ATTR void mwdt_ll_write_protect_disable(timg_dev_t *hw)
{
hw->wdt_wprotect = TIMG_WDT_WKEY_VALUE;
}
/**
* @brief Clear the MWDT interrupt status.
*
* @param hw Start address of the peripheral registers.
*/
FORCE_INLINE_ATTR void mwdt_ll_clear_intr_status(timg_dev_t *hw)
{
hw->int_clr.wdt = 1;
}
/**
* @brief Set the interrupt enable bit for the MWDT interrupt.
*
* @param hw Beginning address of the peripheral registers.
* @param enable Whether to enable the MWDT interrupt
*/
FORCE_INLINE_ATTR void mwdt_ll_set_intr_enable(timg_dev_t *hw, bool enable)
{
hw->int_ena.wdt = (enable) ? 1 : 0;
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,502 @@
// 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 "soc/rmt_struct.h"
#include "soc/soc_caps.h"
#ifdef __cplusplus
extern "C" {
#endif
#define RMT_LL_HW_BASE (&RMT)
#define RMT_LL_MEM_BASE (&RMTMEM)
// Note: TX and RX channel number are all index from zero in the LL driver
// i.e. tx_channel belongs to [0,2], and rx_channel belongs to [0,2]
static inline void rmt_ll_enable_drive_clock(rmt_dev_t *dev, bool enable)
{
dev->sys_conf.clk_en = enable; // register clock gating
dev->sys_conf.mem_clk_force_on = enable; // memory clock gating
}
static inline void rmt_ll_power_down_mem(rmt_dev_t *dev, bool enable)
{
dev->sys_conf.mem_force_pu = !enable;
dev->sys_conf.mem_force_pd = enable;
}
static inline bool rmt_ll_is_mem_power_down(rmt_dev_t *dev)
{
// the RTC domain can also power down RMT memory
// so it's probably not enough to detect whether it's powered down or not
// mem_force_pd has higher priority than mem_force_pu
return (dev->sys_conf.mem_force_pd) || !(dev->sys_conf.mem_force_pu);
}
static inline void rmt_ll_enable_mem_access(rmt_dev_t *dev, bool enable)
{
dev->sys_conf.fifo_mask = enable;
}
static inline void rmt_ll_set_group_clock_src(rmt_dev_t *dev, uint32_t channel, uint8_t src, uint8_t div_num, uint8_t div_a, uint8_t div_b)
{
// Formula: rmt_sclk = module_clock_src / (1 + div_num + div_a / div_b)
dev->sys_conf.sclk_active = 0;
dev->sys_conf.sclk_sel = src;
dev->sys_conf.sclk_div_num = div_num;
dev->sys_conf.sclk_div_a = div_a;
dev->sys_conf.sclk_div_b = div_b;
dev->sys_conf.sclk_active = 1;
}
static inline uint32_t rmt_ll_get_group_clock_src(rmt_dev_t *dev, uint32_t channel)
{
return dev->sys_conf.sclk_sel;
}
static inline void rmt_ll_tx_reset_channel_clock_div(rmt_dev_t *dev, uint32_t channel)
{
dev->ref_cnt_rst.val |= (1 << channel);
}
static inline void rmt_ll_tx_reset_channels_clock_div(rmt_dev_t *dev, uint32_t channel_mask)
{
dev->ref_cnt_rst.val |= channel_mask;
}
static inline void rmt_ll_rx_reset_channel_clock_div(rmt_dev_t *dev, uint32_t channel)
{
dev->ref_cnt_rst.val |= (1 << (channel + 2));
}
static inline void rmt_ll_tx_reset_pointer(rmt_dev_t *dev, uint32_t channel)
{
dev->tx_conf[channel].mem_rd_rst = 1;
dev->tx_conf[channel].mem_rd_rst = 0;
dev->tx_conf[channel].mem_rst = 1;
dev->tx_conf[channel].mem_rst = 0;
}
static inline void rmt_ll_rx_reset_pointer(rmt_dev_t *dev, uint32_t channel)
{
dev->rx_conf[channel].conf1.mem_wr_rst = 1;
dev->rx_conf[channel].conf1.mem_wr_rst = 0;
dev->rx_conf[channel].conf1.mem_rst = 1;
dev->rx_conf[channel].conf1.mem_rst = 0;
}
static inline void rmt_ll_tx_start(rmt_dev_t *dev, uint32_t channel)
{
dev->tx_conf[channel].conf_update = 1;
dev->tx_conf[channel].tx_start = 1;
}
static inline void rmt_ll_tx_stop(rmt_dev_t *dev, uint32_t channel)
{
dev->tx_conf[channel].tx_stop = 1;
dev->tx_conf[channel].conf_update = 1;
}
static inline void rmt_ll_rx_enable(rmt_dev_t *dev, uint32_t channel, bool enable)
{
dev->rx_conf[channel].conf1.rx_en = enable;
dev->rx_conf[channel].conf1.conf_update = 1;
}
static inline void rmt_ll_tx_set_mem_blocks(rmt_dev_t *dev, uint32_t channel, uint8_t block_num)
{
dev->tx_conf[channel].mem_size = block_num;
}
static inline void rmt_ll_rx_set_mem_blocks(rmt_dev_t *dev, uint32_t channel, uint8_t block_num)
{
dev->rx_conf[channel].conf0.mem_size = block_num;
}
static inline uint32_t rmt_ll_tx_get_mem_blocks(rmt_dev_t *dev, uint32_t channel)
{
return dev->tx_conf[channel].mem_size;
}
static inline uint32_t rmt_ll_rx_get_mem_blocks(rmt_dev_t *dev, uint32_t channel)
{
return dev->rx_conf[channel].conf0.mem_size;
}
static inline void rmt_ll_tx_set_channel_clock_div(rmt_dev_t *dev, uint32_t channel, uint32_t div)
{
dev->tx_conf[channel].div_cnt = div;
}
static inline void rmt_ll_rx_set_channel_clock_div(rmt_dev_t *dev, uint32_t channel, uint32_t div)
{
dev->rx_conf[channel].conf0.div_cnt = div;
}
static inline uint32_t rmt_ll_tx_get_channel_clock_div(rmt_dev_t *dev, uint32_t channel)
{
return dev->tx_conf[channel].div_cnt;
}
static inline uint32_t rmt_ll_rx_get_channel_clock_div(rmt_dev_t *dev, uint32_t channel)
{
return dev->rx_conf[channel].conf0.div_cnt;
}
static inline void rmt_ll_tx_enable_pingpong(rmt_dev_t *dev, uint32_t channel, bool enable)
{
dev->tx_conf[channel].mem_tx_wrap_en = enable;
}
static inline void rmt_ll_rx_set_idle_thres(rmt_dev_t *dev, uint32_t channel, uint32_t thres)
{
dev->rx_conf[channel].conf0.idle_thres = thres;
}
static inline uint32_t rmt_ll_rx_get_idle_thres(rmt_dev_t *dev, uint32_t channel)
{
return dev->rx_conf[channel].conf0.idle_thres;
}
static inline void rmt_ll_rx_set_mem_owner(rmt_dev_t *dev, uint32_t channel, uint8_t owner)
{
dev->rx_conf[channel].conf1.mem_owner = owner;
}
static inline uint32_t rmt_ll_rx_get_mem_owner(rmt_dev_t *dev, uint32_t channel)
{
return dev->rx_conf[channel].conf1.mem_owner;
}
static inline void rmt_ll_tx_enable_loop(rmt_dev_t *dev, uint32_t channel, bool enable)
{
dev->tx_conf[channel].tx_conti_mode = enable;
}
static inline bool rmt_ll_is_tx_loop_enabled(rmt_dev_t *dev, uint32_t channel)
{
return dev->tx_conf[channel].tx_conti_mode;
}
static inline void rmt_ll_tx_set_loop_count(rmt_dev_t *dev, uint32_t channel, uint32_t count)
{
dev->tx_lim[channel].tx_loop_num = count;
}
static inline void rmt_ll_tx_reset_loop(rmt_dev_t *dev, uint32_t channel)
{
dev->tx_lim[channel].loop_count_reset = 1;
dev->tx_lim[channel].loop_count_reset = 0;
}
static inline void rmt_ll_tx_enable_loop_count(rmt_dev_t *dev, uint32_t channel, bool enable)
{
dev->tx_lim[channel].tx_loop_cnt_en = enable;
}
static inline void rmt_ll_tx_enable_sync(rmt_dev_t *dev, bool enable)
{
dev->tx_sim.en = enable;
}
static inline void rmt_ll_tx_add_to_sync_group(rmt_dev_t *dev, uint32_t channel)
{
dev->tx_sim.val |= 1 << channel;
}
static inline void rmt_ll_tx_remove_from_sync_group(rmt_dev_t *dev, uint32_t channel)
{
dev->tx_sim.val &= ~(1 << channel);
}
static inline void rmt_ll_rx_enable_filter(rmt_dev_t *dev, uint32_t channel, bool enable)
{
dev->rx_conf[channel].conf1.rx_filter_en = enable;
}
static inline void rmt_ll_rx_set_filter_thres(rmt_dev_t *dev, uint32_t channel, uint32_t thres)
{
dev->rx_conf[channel].conf1.rx_filter_thres = thres;
}
static inline void rmt_ll_tx_enable_idle(rmt_dev_t *dev, uint32_t channel, bool enable)
{
dev->tx_conf[channel].idle_out_en = enable;
}
static inline bool rmt_ll_is_tx_idle_enabled(rmt_dev_t *dev, uint32_t channel)
{
return dev->tx_conf[channel].idle_out_en;
}
static inline void rmt_ll_tx_set_idle_level(rmt_dev_t *dev, uint32_t channel, uint8_t level)
{
dev->tx_conf[channel].idle_out_lv = level;
}
static inline uint32_t rmt_ll_tx_get_idle_level(rmt_dev_t *dev, uint32_t channel)
{
return dev->tx_conf[channel].idle_out_lv;
}
static inline uint32_t rmt_ll_rx_get_channel_status(rmt_dev_t *dev, uint32_t channel)
{
return dev->rx_status[channel].val;
}
static inline uint32_t rmt_ll_tx_get_channel_status(rmt_dev_t *dev, uint32_t channel)
{
return dev->tx_status[channel].val;
}
static inline void rmt_ll_tx_set_limit(rmt_dev_t *dev, uint32_t channel, uint32_t limit)
{
dev->tx_lim[channel].limit = limit;
}
static inline void rmt_ll_rx_set_limit(rmt_dev_t *dev, uint32_t channel, uint32_t limit)
{
dev->rx_lim[channel].rx_lim = limit;
}
static inline uint32_t rmt_ll_rx_get_limit(rmt_dev_t *dev, uint32_t channel)
{
return dev->rx_lim[channel].rx_lim;
}
static inline void rmt_ll_enable_tx_end_interrupt(rmt_dev_t *dev, uint32_t channel, bool enable)
{
if (enable) {
dev->int_ena.val |= (1 << channel);
} else {
dev->int_ena.val &= ~(1 << channel);
}
}
static inline void rmt_ll_enable_tx_err_interrupt(rmt_dev_t *dev, uint32_t channel, bool enable)
{
if (enable) {
dev->int_ena.val |= (1 << (channel + 4));
} else {
dev->int_ena.val &= ~(1 << (channel + 4));
}
}
static inline void rmt_ll_enable_rx_end_interrupt(rmt_dev_t *dev, uint32_t channel, bool enable)
{
if (enable) {
dev->int_ena.val |= (1 << (channel + 2));
} else {
dev->int_ena.val &= ~(1 << (channel + 2));
}
}
static inline void rmt_ll_enable_rx_err_interrupt(rmt_dev_t *dev, uint32_t channel, bool enable)
{
if (enable) {
dev->int_ena.val |= (1 << (channel + 6));
} else {
dev->int_ena.val &= ~(1 << (channel + 6));
}
}
static inline void rmt_ll_enable_tx_thres_interrupt(rmt_dev_t *dev, uint32_t channel, bool enable)
{
if (enable) {
dev->int_ena.val |= (1 << (channel + 8));
} else {
dev->int_ena.val &= ~(1 << (channel + 8));
}
}
static inline void rmt_ll_enable_tx_loop_interrupt(rmt_dev_t *dev, uint32_t channel, bool enable)
{
if (enable) {
dev->int_ena.val |= (1 << (channel + 12));
} else {
dev->int_ena.val &= ~(1 << (channel + 12));
}
}
static inline void rmt_ll_enable_rx_thres_interrupt(rmt_dev_t *dev, uint32_t channel, bool enable)
{
if (enable) {
dev->int_ena.val |= (1 << (channel + 10));
} else {
dev->int_ena.val &= ~(1 << (channel + 10));
}
}
static inline void rmt_ll_clear_tx_end_interrupt(rmt_dev_t *dev, uint32_t channel)
{
dev->int_clr.val = (1 << (channel));
}
static inline void rmt_ll_clear_rx_end_interrupt(rmt_dev_t *dev, uint32_t channel)
{
dev->int_clr.val = (1 << (channel + 2));
}
static inline void rmt_ll_clear_tx_err_interrupt(rmt_dev_t *dev, uint32_t channel)
{
dev->int_clr.val = (1 << (channel + 4));
}
static inline void rmt_ll_clear_rx_err_interrupt(rmt_dev_t *dev, uint32_t channel)
{
dev->int_clr.val = (1 << (channel + 6));
}
static inline void rmt_ll_clear_tx_thres_interrupt(rmt_dev_t *dev, uint32_t channel)
{
dev->int_clr.val = (1 << (channel + 8));
}
static inline void rmt_ll_clear_tx_loop_interrupt(rmt_dev_t *dev, uint32_t channel)
{
dev->int_clr.val = (1 << (channel + 12));
}
static inline void rmt_ll_clear_rx_thres_interrupt(rmt_dev_t *dev, uint32_t channel)
{
dev->int_clr.val = (1 << (channel + 10));
}
static inline uint32_t rmt_ll_get_tx_end_interrupt_status(rmt_dev_t *dev)
{
return dev->int_st.val & 0x03;
}
static inline uint32_t rmt_ll_get_rx_end_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 2) & 0x03;
}
static inline uint32_t rmt_ll_get_tx_err_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 4) & 0x03;
}
static inline uint32_t rmt_ll_get_rx_err_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 6) & 0x03;
}
static inline uint32_t rmt_ll_get_tx_thres_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 8) & 0x03;
}
static inline uint32_t rmt_ll_get_rx_thres_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 10) & 0x03;
}
static inline uint32_t rmt_ll_get_tx_loop_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 12) & 0x03;
}
static inline void rmt_ll_tx_set_carrier_high_low_ticks(rmt_dev_t *dev, uint32_t channel, uint32_t high_ticks, uint32_t low_ticks)
{
// In case the compiler optimise a 32bit instruction (e.g. s32i) into two 16bit instruction (e.g. s16i, which is not allowed to access a register)
// We take care of the "read-modify-write" procedure by ourselves.
typeof(dev->tx_carrier[0]) reg;
reg.high = high_ticks;
reg.low = low_ticks;
dev->tx_carrier[channel].val = reg.val;
}
static inline void rmt_ll_rx_set_carrier_high_low_ticks(rmt_dev_t *dev, uint32_t channel, uint32_t high_ticks, uint32_t low_ticks)
{
typeof(dev->rx_carrier[0]) reg;
reg.high_thres = high_ticks;
reg.low_thres = low_ticks;
dev->rx_carrier[channel].val = reg.val;
}
static inline void rmt_ll_tx_get_carrier_high_low_ticks(rmt_dev_t *dev, uint32_t channel, uint32_t *high_ticks, uint32_t *low_ticks)
{
*high_ticks = dev->tx_carrier[channel].high;
*low_ticks = dev->tx_carrier[channel].low;
}
static inline void rmt_ll_rx_get_carrier_high_low_ticks(rmt_dev_t *dev, uint32_t channel, uint32_t *high_ticks, uint32_t *low_ticks)
{
*high_ticks = dev->rx_carrier[channel].high_thres;
*low_ticks = dev->rx_carrier[channel].low_thres;
}
static inline void rmt_ll_tx_enable_carrier_modulation(rmt_dev_t *dev, uint32_t channel, bool enable)
{
dev->tx_conf[channel].carrier_en = enable;
}
static inline void rmt_ll_rx_enable_carrier_demodulation(rmt_dev_t *dev, uint32_t channel, bool enable)
{
dev->rx_conf[channel].conf0.carrier_en = enable;
}
static inline void rmt_ll_tx_set_carrier_level(rmt_dev_t *dev, uint32_t channel, uint8_t level)
{
dev->tx_conf[channel].carrier_out_lv = level;
}
static inline void rmt_ll_rx_set_carrier_level(rmt_dev_t *dev, uint32_t channel, uint8_t level)
{
dev->rx_conf[channel].conf0.carrier_out_lv = level;
}
// set true, enable carrier in all RMT state (idle, reading, sending)
// set false, enable carrier only in sending state (i.e. there're effective data in RAM to be sent)
static inline void rmt_ll_tx_set_carrier_always_on(rmt_dev_t *dev, uint32_t channel, bool enable)
{
dev->tx_conf[channel].carrier_eff_en = !enable;
}
//Writes items to the specified TX channel memory with the given offset and writen length.
//the caller should ensure that (length + off) <= (memory block * SOC_RMT_MEM_WORDS_PER_CHANNEL)
static inline void rmt_ll_write_memory(rmt_mem_t *mem, uint32_t channel, const rmt_item32_t *data, uint32_t length, uint32_t off)
{
for (uint32_t i = 0; i < length; i++) {
mem->chan[channel].data32[i + off].val = data[i].val;
}
}
static inline void rmt_ll_rx_enable_pingpong(rmt_dev_t *dev, uint32_t channel, bool enable)
{
dev->rx_conf[channel].conf1.mem_rx_wrap_en = enable;
}
/************************************************************************************************
* Following Low Level APIs only used for backward compatible, will be deprecated in the IDF v5.0
***********************************************************************************************/
static inline void rmt_ll_set_intr_enable_mask(uint32_t mask)
{
RMT.int_ena.val |= mask;
}
static inline void rmt_ll_clr_intr_enable_mask(uint32_t mask)
{
RMT.int_ena.val &= (~mask);
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,67 @@
// 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 "soc/soc.h"
#include "soc/rtc.h"
#include "soc/rtc_cntl_reg.h"
#include "soc/apb_ctrl_reg.h"
#ifdef __cplusplus
extern "C" {
#endif
static inline void rtc_cntl_ll_set_wakeup_timer(uint64_t t)
{
WRITE_PERI_REG(RTC_CNTL_SLP_TIMER0_REG, t & UINT32_MAX);
WRITE_PERI_REG(RTC_CNTL_SLP_TIMER1_REG, t >> 32);
SET_PERI_REG_MASK(RTC_CNTL_INT_CLR_REG, RTC_CNTL_MAIN_TIMER_INT_CLR_M);
SET_PERI_REG_MASK(RTC_CNTL_SLP_TIMER1_REG, RTC_CNTL_MAIN_TIMER_ALARM_EN_M);
}
static inline uint32_t rtc_cntl_ll_gpio_get_wakeup_pins(void)
{
return GET_PERI_REG_MASK(RTC_CNTL_GPIO_WAKEUP_REG, RTC_CNTL_GPIO_WAKEUP_STATUS);
}
static inline void rtc_cntl_ll_gpio_set_wakeup_pins(void)
{
REG_CLR_BIT(RTC_CNTL_GPIO_WAKEUP_REG, RTC_CNTL_GPIO_WAKEUP_STATUS_CLR);
}
static inline void rtc_cntl_ll_gpio_clear_wakeup_pins(void)
{
REG_SET_BIT(RTC_CNTL_GPIO_WAKEUP_REG, RTC_CNTL_GPIO_WAKEUP_STATUS_CLR);
}
static inline void rtc_cntl_ll_enable_cpu_retention(uint32_t addr)
{
/* write memory address to register */
REG_SET_FIELD(APB_CTRL_RETENTION_CTRL_REG, APB_CTRL_RETENTION_LINK_ADDR, (uint32_t)addr);
/* Enable clock */
REG_SET_BIT(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_DIG_CLK8M_EN);
/* Enable retention when cpu sleep enable */
REG_SET_BIT(RTC_CNTL_RETENTION_CTRL_REG, RTC_CNTL_RETENTION_EN);
}
static inline void rtc_cntl_ll_disable_cpu_retention(void)
{
REG_CLR_BIT(RTC_CNTL_RETENTION_CTRL_REG, RTC_CNTL_RETENTION_EN);
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,311 @@
// 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.
// The LL layer for Timer Group register operations.
// Note that most of the register operations in this layer are non-atomic operations.
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include <stdlib.h>
#include <stdbool.h>
#include "hal/wdt_types.h"
#include "soc/rtc_cntl_periph.h"
#include "soc/efuse_reg.h"
#include "esp_attr.h"
//Type check wdt_stage_action_t
_Static_assert(WDT_STAGE_ACTION_OFF == RTC_WDT_STG_SEL_OFF, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_stage_action_t");
_Static_assert(WDT_STAGE_ACTION_INT == RTC_WDT_STG_SEL_INT, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_stage_action_t");
_Static_assert(WDT_STAGE_ACTION_RESET_CPU == RTC_WDT_STG_SEL_RESET_CPU, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_stage_action_t");
_Static_assert(WDT_STAGE_ACTION_RESET_SYSTEM == RTC_WDT_STG_SEL_RESET_SYSTEM, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_stage_action_t");
_Static_assert(WDT_STAGE_ACTION_RESET_RTC == RTC_WDT_STG_SEL_RESET_RTC, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_stage_action_t");
//Type check wdt_reset_sig_length_t
_Static_assert(WDT_RESET_SIG_LENGTH_100ns == RTC_WDT_RESET_LENGTH_100_NS, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_reset_sig_length_t");
_Static_assert(WDT_RESET_SIG_LENGTH_200ns == RTC_WDT_RESET_LENGTH_200_NS, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_reset_sig_length_t");
_Static_assert(WDT_RESET_SIG_LENGTH_300ns == RTC_WDT_RESET_LENGTH_300_NS, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_reset_sig_length_t");
_Static_assert(WDT_RESET_SIG_LENGTH_400ns == RTC_WDT_RESET_LENGTH_400_NS, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_reset_sig_length_t");
_Static_assert(WDT_RESET_SIG_LENGTH_500ns == RTC_WDT_RESET_LENGTH_500_NS, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_reset_sig_length_t");
_Static_assert(WDT_RESET_SIG_LENGTH_800ns == RTC_WDT_RESET_LENGTH_800_NS, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_reset_sig_length_t");
_Static_assert(WDT_RESET_SIG_LENGTH_1_6us == RTC_WDT_RESET_LENGTH_1600_NS, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_reset_sig_length_t");
_Static_assert(WDT_RESET_SIG_LENGTH_3_2us == RTC_WDT_RESET_LENGTH_3200_NS, "Add mapping to LL watchdog timeout behavior, since it's no longer naturally compatible with wdt_reset_sig_length_t");
/**
* @brief Enable the RWDT
*
* @param hw Start address of the peripheral registers.
*/
FORCE_INLINE_ATTR void rwdt_ll_enable(rtc_cntl_dev_t *hw)
{
hw->wdt_config0.en = 1;
}
/**
* @brief Disable the RWDT
*
* @param hw Start address of the peripheral registers.
* @note This function does not disable the flashboot mode. Therefore, given that
* the MWDT is disabled using this function, a timeout can still occur
* if the flashboot mode is simultaneously enabled.
*/
FORCE_INLINE_ATTR void rwdt_ll_disable(rtc_cntl_dev_t *hw)
{
hw->wdt_config0.en = 0;
}
/**
* @brief Check if the RWDT is enabled
*
* @param hw Start address of the peripheral registers.
* @return True if RTC WDT is enabled
*/
FORCE_INLINE_ATTR bool rwdt_ll_check_if_enabled(rtc_cntl_dev_t *hw)
{
return (hw->wdt_config0.en) ? true : false;
}
/**
* @brief Configure a particular stage of the RWDT
*
* @param hw Start address of the peripheral registers.
* @param stage Which stage to configure
* @param timeout Number of timer ticks for the stage to timeout (see note).
* @param behavior What action to take when the stage times out
*
* @note The value of of RWDT stage 0 timeout register is special, in
* that an implicit multiplier is applied to that value to produce
* and effective timeout tick value. The multiplier is dependent
* on an EFuse value. Therefore, when configuring stage 0, the valid
* values for the timeout argument are:
* - If Efuse value is 0, any even number between [2,2*UINT32_MAX]
* - If Efuse value is 1, any multiple of 4 between [4,4*UINT32_MAX]
* - If Efuse value is 2, any multiple of 8 between [8,8*UINT32_MAX]
* - If Efuse value is 3, any multiple of 16 between [16,16*UINT32_MAX]
*/
FORCE_INLINE_ATTR void rwdt_ll_config_stage(rtc_cntl_dev_t *hw, wdt_stage_t stage, uint32_t timeout_ticks, wdt_stage_action_t behavior)
{
switch (stage) {
case WDT_STAGE0:
hw->wdt_config0.stg0 = behavior;
//Account of implicty multiplier applied to stage 0 timeout tick config value
hw->wdt_config1 = timeout_ticks >> (1 + REG_GET_FIELD(EFUSE_RD_REPEAT_DATA1_REG, EFUSE_WDT_DELAY_SEL));
break;
case WDT_STAGE1:
hw->wdt_config0.stg1 = behavior;
hw->wdt_config2 = timeout_ticks;
break;
case WDT_STAGE2:
hw->wdt_config0.stg2 = behavior;
hw->wdt_config3 = timeout_ticks;
break;
case WDT_STAGE3:
hw->wdt_config0.stg3 = behavior;
hw->wdt_config4 = timeout_ticks;
break;
default:
abort();
}
}
/**
* @brief Disable a particular stage of the RWDT
*
* @param hw Start address of the peripheral registers.
* @param stage Which stage to disable
*/
FORCE_INLINE_ATTR void rwdt_ll_disable_stage(rtc_cntl_dev_t *hw, wdt_stage_t stage)
{
switch (stage) {
case WDT_STAGE0:
hw->wdt_config0.stg0 = WDT_STAGE_ACTION_OFF;
break;
case WDT_STAGE1:
hw->wdt_config0.stg1 = WDT_STAGE_ACTION_OFF;
break;
case WDT_STAGE2:
hw->wdt_config0.stg2 = WDT_STAGE_ACTION_OFF;
break;
case WDT_STAGE3:
hw->wdt_config0.stg3 = WDT_STAGE_ACTION_OFF;
break;
default:
abort();
}
}
/**
* @brief Set the length of the CPU reset action
*
* @param hw Start address of the peripheral registers.
* @param length Length of CPU reset signal
*/
FORCE_INLINE_ATTR void rwdt_ll_set_cpu_reset_length(rtc_cntl_dev_t *hw, wdt_reset_sig_length_t length)
{
hw->wdt_config0.cpu_reset_length = length;
}
/**
* @brief Set the length of the system reset action
*
* @param hw Start address of the peripheral registers.
* @param length Length of system reset signal
*/
FORCE_INLINE_ATTR void rwdt_ll_set_sys_reset_length(rtc_cntl_dev_t *hw, wdt_reset_sig_length_t length)
{
hw->wdt_config0.sys_reset_length = length;
}
/**
* @brief Enable/Disable the RWDT flashboot mode.
*
* @param hw Start address of the peripheral registers.
* @param enable True to enable RWDT flashboot mode, false to disable RWDT flashboot mode.
*
* @note Flashboot mode is independent and can trigger a WDT timeout event if the
* WDT's enable bit is set to 0. Flashboot mode for RWDT is automatically enabled
* on flashboot, and should be disabled by software when flashbooting completes.
*/
FORCE_INLINE_ATTR void rwdt_ll_set_flashboot_en(rtc_cntl_dev_t *hw, bool enable)
{
hw->wdt_config0.flashboot_mod_en = (enable) ? 1 : 0;
}
/**
* @brief Enable/Disable the CPU0 to be reset on WDT_STAGE_ACTION_RESET_CPU
*
* @param hw Start address of the peripheral registers.
* @param enable True to enable CPU0 to be reset, false to disable.
*/
FORCE_INLINE_ATTR void rwdt_ll_set_procpu_reset_en(rtc_cntl_dev_t *hw, bool enable)
{
hw->wdt_config0.procpu_reset_en = (enable) ? 1 : 0;
}
/**
* @brief Enable/Disable the CPU1 to be reset on WDT_STAGE_ACTION_RESET_CPU
*
* @param hw Start address of the peripheral registers.
* @param enable True to enable CPU1 to be reset, false to disable.
*/
FORCE_INLINE_ATTR void rwdt_ll_set_appcpu_reset_en(rtc_cntl_dev_t *hw, bool enable)
{
hw->wdt_config0.appcpu_reset_en = (enable) ? 1 : 0;
}
/**
* @brief Enable/Disable the RWDT pause during sleep functionality
*
* @param hw Start address of the peripheral registers.
* @param enable True to enable, false to disable.
*/
FORCE_INLINE_ATTR void rwdt_ll_set_pause_in_sleep_en(rtc_cntl_dev_t *hw, bool enable)
{
hw->wdt_config0.pause_in_slp = (enable) ? 1 : 0;
}
/**
* @brief Enable/Disable chip reset on RWDT timeout.
*
* A chip reset also resets the analog portion of the chip. It will appear as a
* POWERON reset rather than an RTC reset.
*
* @param hw Start address of the peripheral registers.
* @param enable True to enable, false to disable.
*/
FORCE_INLINE_ATTR void rwdt_ll_set_chip_reset_en(rtc_cntl_dev_t *hw, bool enable)
{
hw->wdt_config0.chip_reset_en = (enable) ? 1 : 0;
}
/**
* @brief Set width of chip reset signal
*
* @param hw Start address of the peripheral registers.
* @param width Width of chip reset signal in terms of number of RTC_SLOW_CLK cycles
*/
FORCE_INLINE_ATTR void rwdt_ll_set_chip_reset_width(rtc_cntl_dev_t *hw, uint32_t width)
{
hw->wdt_config0.chip_reset_width = width;
}
/**
* @brief Feed the RWDT
*
* Resets the current timer count and current stage.
*
* @param hw Start address of the peripheral registers.
*/
FORCE_INLINE_ATTR void rwdt_ll_feed(rtc_cntl_dev_t *hw)
{
hw->wdt_feed.feed = 1;
}
/**
* @brief Enable write protection of the RWDT registers
*
* @param hw Start address of the peripheral registers.
*/
FORCE_INLINE_ATTR void rwdt_ll_write_protect_enable(rtc_cntl_dev_t *hw)
{
hw->wdt_wprotect = 0;
}
/**
* @brief Disable write protection of the RWDT registers
*
* @param hw Start address of the peripheral registers.
*/
FORCE_INLINE_ATTR void rwdt_ll_write_protect_disable(rtc_cntl_dev_t *hw)
{
hw->wdt_wprotect = RTC_CNTL_WDT_WKEY_VALUE;
}
/**
* @brief Enable the RWDT interrupt.
*
* @param hw Start address of the peripheral registers.
* @param enable True to enable RWDT interrupt, false to disable.
*/
FORCE_INLINE_ATTR void rwdt_ll_set_intr_enable(rtc_cntl_dev_t *hw, bool enable)
{
hw->int_ena.rtc_wdt = (enable) ? 1 : 0;
}
/**
* @brief Check if the RWDT interrupt has been triggered
*
* @param hw Start address of the peripheral registers.
* @return True if the RWDT interrupt was triggered
*/
FORCE_INLINE_ATTR bool rwdt_ll_check_intr_status(rtc_cntl_dev_t *hw)
{
return (hw->int_st.rtc_wdt) ? true : false;
}
/**
* @brief Clear the RWDT interrupt status.
*
* @param hw Start address of the peripheral registers.
*/
FORCE_INLINE_ATTR void rwdt_ll_clear_intr_status(rtc_cntl_dev_t *hw)
{
hw->int_clr.rtc_wdt = 1;
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,157 @@
// 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 <stdbool.h>
#include "soc/hwcrypto_reg.h"
#include "hal/sha_types.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Start a new SHA block conversions (no initial hash in HW)
*
* @param sha_type The SHA algorithm type
*/
static inline void sha_ll_start_block(esp_sha_type sha_type)
{
REG_WRITE(SHA_MODE_REG, sha_type);
REG_WRITE(SHA_START_REG, 1);
}
/**
* @brief Continue a SHA block conversion (initial hash in HW)
*
* @param sha_type The SHA algorithm type
*/
static inline void sha_ll_continue_block(esp_sha_type sha_type)
{
REG_WRITE(SHA_MODE_REG, sha_type);
REG_WRITE(SHA_CONTINUE_REG, 1);
}
/**
* @brief Start a new SHA message conversion using DMA (no initial hash in HW)
*
* @param sha_type The SHA algorithm type
*/
static inline void sha_ll_start_dma(esp_sha_type sha_type)
{
REG_WRITE(SHA_MODE_REG, sha_type);
REG_WRITE(SHA_DMA_START_REG, 1);
}
/**
* @brief Continue a SHA message conversion using DMA (initial hash in HW)
*
* @param sha_type The SHA algorithm type
*/
static inline void sha_ll_continue_dma(esp_sha_type sha_type)
{
REG_WRITE(SHA_MODE_REG, sha_type);
REG_WRITE(SHA_DMA_CONTINUE_REG, 1);
}
/**
* @brief Load the current hash digest to digest register
*
* @note Happens automatically on ESP32S3
*
* @param sha_type The SHA algorithm type
*/
static inline void sha_ll_load(esp_sha_type sha_type)
{
}
/**
* @brief Sets the number of message blocks to be hashed
*
* @note DMA operation only
*
* @param num_blocks Number of message blocks to process
*/
static inline void sha_ll_set_block_num(size_t num_blocks)
{
REG_WRITE(SHA_BLOCK_NUM_REG, num_blocks);
}
/**
* @brief Checks if the SHA engine is currently busy hashing a block
*
* @return true SHA engine busy
* @return false SHA engine idle
*/
static inline bool sha_ll_busy(void)
{
return REG_READ(SHA_BUSY_REG);
}
/**
* @brief Write a text (message) block to the SHA engine
*
* @param input_text Input buffer to be written to the SHA engine
* @param block_word_len Number of words in block
*/
static inline void sha_ll_fill_text_block(const void *input_text, size_t block_word_len)
{
uint32_t *data_words = (uint32_t *)input_text;
uint32_t *reg_addr_buf = (uint32_t *)(SHA_TEXT_BASE);
for (int i = 0; i < block_word_len; i++) {
REG_WRITE(&reg_addr_buf[i], data_words[i]);
}
}
/**
* @brief Read the message digest from the SHA engine
*
* @param sha_type The SHA algorithm type
* @param digest_state Buffer that message digest will be written to
* @param digest_word_len Length of the message digest
*/
static inline void sha_ll_read_digest(esp_sha_type sha_type, void *digest_state, size_t digest_word_len)
{
uint32_t *digest_state_words = (uint32_t *)digest_state;
const size_t REG_WIDTH = sizeof(uint32_t);
for (size_t i = 0; i < digest_word_len; i++) {
digest_state_words[i] = REG_READ(SHA_H_BASE + (i * REG_WIDTH));
}
}
/**
* @brief Write the message digest to the SHA engine
*
* @param sha_type The SHA algorithm type
* @param digest_state Message digest to be written to SHA engine
* @param digest_word_len Length of the message digest
*/
static inline void sha_ll_write_digest(esp_sha_type sha_type, void *digest_state, size_t digest_word_len)
{
uint32_t *digest_state_words = (uint32_t *)digest_state;
uint32_t *reg_addr_buf = (uint32_t *)(SHA_H_BASE);
for (int i = 0; i < digest_word_len; i++) {
REG_WRITE(&reg_addr_buf[i], digest_state_words[i]);
}
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,73 @@
// 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.
/*******************************************************************************
* NOTICE
* The hal is not public api, don't use in application code.
* See readme.md in soc/include/hal/readme.md
******************************************************************************/
// The LL layer for ESP32 SIGMADELTA register operations
#pragma once
#include <stdbool.h>
#include "soc/sigmadelta_periph.h"
#include "hal/sigmadelta_types.h"
#ifdef __cplusplus
extern "C" {
#endif
// Get SIGMADELTA hardware instance with giving sigmadelta num
#define SIGMADELTA_LL_GET_HW(num) (((num) == 0) ? (&SIGMADELTA) : NULL)
/**
* @brief Set Sigma-delta enable
*
* @param hw Peripheral SIGMADELTA hardware instance address.
* @param en Sigma-delta enable value
*/
static inline void sigmadelta_ll_set_en(gpio_sd_dev_t *hw, bool en)
{
hw->misc.function_clk_en = en;
}
/**
* @brief Set Sigma-delta channel duty.
*
* @param hw Peripheral SIGMADELTA hardware instance address.
* @param channel Sigma-delta channel number
* @param duty Sigma-delta duty of one channel, the value ranges from -128 to 127, recommended range is -90 ~ 90.
* The waveform is more like a random one in this range.
*/
static inline void sigmadelta_ll_set_duty(gpio_sd_dev_t *hw, sigmadelta_channel_t channel, int8_t duty)
{
hw->channel[channel].duty = duty;
}
/**
* @brief Set Sigma-delta channel's clock pre-scale value.
*
* @param hw Peripheral SIGMADELTA hardware instance address.
* @param channel Sigma-delta channel number
* @param val The divider of source clock, ranges from 0 to 255
*/
static inline void sigmadelta_ll_set_prescale(gpio_sd_dev_t *hw, sigmadelta_channel_t channel, uint8_t prescale)
{
hw->channel[channel].prescale = prescale;
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,52 @@
// 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 "soc/soc.h"
#include "soc/rtc_cntl_reg.h"
#include "soc/soc_caps.h"
#ifdef __cplusplus
extern "C" {
#endif
static inline void soc_ll_stall_core(int core)
{
const int rtc_cntl_c1_m[SOC_CPU_CORES_NUM] = {RTC_CNTL_SW_STALL_PROCPU_C1_M};
const int rtc_cntl_c1_s[SOC_CPU_CORES_NUM] = {RTC_CNTL_SW_STALL_PROCPU_C1_S};
const int rtc_cntl_c0_m[SOC_CPU_CORES_NUM] = {RTC_CNTL_SW_STALL_PROCPU_C0_M};
const int rtc_cntl_c0_s[SOC_CPU_CORES_NUM] = {RTC_CNTL_SW_STALL_PROCPU_C0_S};
CLEAR_PERI_REG_MASK(RTC_CNTL_SW_CPU_STALL_REG, rtc_cntl_c1_m[core]);
SET_PERI_REG_MASK(RTC_CNTL_SW_CPU_STALL_REG, 0x21 << rtc_cntl_c1_s[core]);
CLEAR_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG, rtc_cntl_c0_m[core]);
SET_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG, 2 << rtc_cntl_c0_s[core]);
}
static inline void soc_ll_unstall_core(int core)
{
const int rtc_cntl_c1_m[SOC_CPU_CORES_NUM] = {RTC_CNTL_SW_STALL_PROCPU_C1_M};
const int rtc_cntl_c0_m[SOC_CPU_CORES_NUM] = {RTC_CNTL_SW_STALL_PROCPU_C0_M};
CLEAR_PERI_REG_MASK(RTC_CNTL_SW_CPU_STALL_REG, rtc_cntl_c1_m[core]);
CLEAR_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG, rtc_cntl_c0_m[core]);
}
static inline void soc_ll_reset_core(int core)
{
SET_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG, RTC_CNTL_SW_PROCPU_RST_M);
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,157 @@
// Copyright 2015-2021 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.
/*******************************************************************************
* NOTICE
* The ll is not public api, don't use in application code.
* See readme.md in hal/include/hal/readme.md
******************************************************************************/
// The Lowlevel layer for SPI Flash Encryption.
#include "soc/system_reg.h"
#include "soc/hwcrypto_reg.h"
#include "soc/soc.h"
#include "string.h"
#include "assert.h"
#include <stdbool.h>
#ifdef __cplusplus
extern "C" {
#endif
/// Choose type of chip you want to encrypt manully
typedef enum
{
FLASH_ENCRYPTION_MANU = 0, ///!< Manually encrypt the flash chip.
PSRAM_ENCRYPTION_MANU = 1 ///!< Manually encrypt the psram chip.
} flash_encrypt_ll_type_t;
/**
* Enable the flash encryption function under spi boot mode and download boot mode.
*/
static inline void spi_flash_encrypt_ll_enable(void)
{
REG_SET_BIT(SYSTEM_EXTERNAL_DEVICE_ENCRYPT_DECRYPT_CONTROL_REG,
SYSTEM_ENABLE_DOWNLOAD_MANUAL_ENCRYPT |
SYSTEM_ENABLE_SPI_MANUAL_ENCRYPT);
}
/*
* Disable the flash encryption mode.
*/
static inline void spi_flash_encrypt_ll_disable(void)
{
REG_CLR_BIT(SYSTEM_EXTERNAL_DEVICE_ENCRYPT_DECRYPT_CONTROL_REG,
SYSTEM_ENABLE_SPI_MANUAL_ENCRYPT);
}
/**
* Choose type of chip you want to encrypt manully
*
* @param type The type of chip to be encrypted
*
* @note The hardware currently support flash encryption.
*/
static inline void spi_flash_encrypt_ll_type(flash_encrypt_ll_type_t type)
{
// Our hardware only support flash encryption
assert(type == FLASH_ENCRYPTION_MANU);
REG_WRITE(AES_XTS_DESTINATION_REG, type);
}
/**
* Configure the data size of a single encryption.
*
* @param block_size Size of the desired block.
*/
static inline void spi_flash_encrypt_ll_buffer_length(uint32_t size)
{
// Desired block should not be larger than the block size.
REG_WRITE(AES_XTS_SIZE_REG, size >> 5);
}
/**
* Save 32-bit piece of plaintext.
*
* @param address the address of written flash partition.
* @param buffer Buffer to store the input data.
* @param size Buffer size.
*
*/
static inline void spi_flash_encrypt_ll_plaintext_save(uint32_t address, const uint32_t* buffer, uint32_t size)
{
uint32_t plaintext_offs = (address % 64);
memcpy((void *)(AES_XTS_PLAIN_BASE + plaintext_offs), buffer, size);
}
/**
* Copy the flash address to XTS_AES physical address
*
* @param flash_addr flash address to write.
*/
static inline void spi_flash_encrypt_ll_address_save(uint32_t flash_addr)
{
REG_WRITE(AES_XTS_PHYSICAL_ADDR_REG, flash_addr);
}
/**
* Start flash encryption
*/
static inline void spi_flash_encrypt_ll_calculate_start(void)
{
REG_WRITE(AES_XTS_TRIGGER_REG, 1);
}
/**
* Wait for flash encryption termination
*/
static inline void spi_flash_encrypt_ll_calculate_wait_idle(void)
{
while(REG_READ(AES_XTS_STATE_REG) == 0x1) {
}
}
/**
* Finish the flash encryption and make encrypted result accessible to SPI.
*/
static inline void spi_flash_encrypt_ll_done(void)
{
REG_WRITE(AES_XTS_RELEASE_REG, 1);
while(REG_READ(AES_XTS_STATE_REG) != 0x3) {
}
}
/**
* Set to destroy encrypted result
*/
static inline void spi_flash_encrypt_ll_destroy(void)
{
REG_WRITE(AES_XTS_DESTROY_REG, 1);
}
/**
* Check if is qualified to encrypt the buffer
*
* @param address the address of written flash partition.
* @param length Buffer size.
*/
static inline bool spi_flash_encrypt_ll_check(uint32_t address, uint32_t length)
{
return ((address % length) == 0) ? true : false;
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,111 @@
// 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.
/*******************************************************************************
* NOTICE
* The ll is not public api, don't use in application code.
* See readme.md in soc/include/hal/readme.md
******************************************************************************/
// The Lowlevel layer for SPI Flash
#pragma once
#include "gpspi_flash_ll.h"
#include "spimem_flash_ll.h"
#ifdef __cplusplus
extern "C" {
#endif
// For esp32s2, spimem is equivalent to traditional spi peripherals found
// in esp32. Let the spi flash clock reg definitions reflect this.
#define SPI_FLASH_LL_CLKREG_VAL_5MHZ {.spimem=SPIMEM_FLASH_LL_CLKREG_VAL_5MHZ}
#define SPI_FLASH_LL_CLKREG_VAL_10MHZ {.spimem=SPIMEM_FLASH_LL_CLKREG_VAL_10MHZ}
#define SPI_FLASH_LL_CLKREG_VAL_20MHZ {.spimem=SPIMEM_FLASH_LL_CLKREG_VAL_20MHZ}
#define SPI_FLASH_LL_CLKREG_VAL_26MHZ {.spimem=SPIMEM_FLASH_LL_CLKREG_VAL_26MHZ}
#define SPI_FLASH_LL_CLKREG_VAL_40MHZ {.spimem=SPIMEM_FLASH_LL_CLKREG_VAL_40MHZ}
#define SPI_FLASH_LL_CLKREG_VAL_80MHZ {.spimem=SPIMEM_FLASH_LL_CLKREG_VAL_80MHZ}
#define spi_flash_ll_get_hw(host_id) (((host_id)<=SPI1_HOST ? (spi_dev_t*) spimem_flash_ll_get_hw(host_id) \
: gpspi_flash_ll_get_hw(host_id)))
#define spi_flash_ll_hw_get_id(dev) ({int dev_id = spimem_flash_ll_hw_get_id(dev); \
if (dev_id < 0) {\
dev_id = gpspi_flash_ll_hw_get_id(dev);\
}\
dev_id; \
})
typedef union {
gpspi_flash_ll_clock_reg_t gpspi;
spimem_flash_ll_clock_reg_t spimem;
} spi_flash_ll_clock_reg_t;
#ifdef GPSPI_BUILD
#define spi_flash_ll_reset(dev) gpspi_flash_ll_reset((spi_dev_t*)dev)
#define spi_flash_ll_cmd_is_done(dev) gpspi_flash_ll_cmd_is_done((spi_dev_t*)dev)
#define spi_flash_ll_get_buffer_data(dev, buffer, read_len) gpspi_flash_ll_get_buffer_data((spi_dev_t*)dev, buffer, read_len)
#define spi_flash_ll_set_buffer_data(dev, buffer, len) gpspi_flash_ll_set_buffer_data((spi_dev_t*)dev, buffer, len)
#define spi_flash_ll_user_start(dev) gpspi_flash_ll_user_start((spi_dev_t*)dev)
#define spi_flash_ll_host_idle(dev) gpspi_flash_ll_host_idle((spi_dev_t*)dev)
#define spi_flash_ll_read_phase(dev) gpspi_flash_ll_read_phase((spi_dev_t*)dev)
#define spi_flash_ll_set_cs_pin(dev, pin) gpspi_flash_ll_set_cs_pin((spi_dev_t*)dev, pin)
#define spi_flash_ll_set_read_mode(dev, read_mode) gpspi_flash_ll_set_read_mode((spi_dev_t*)dev, read_mode)
#define spi_flash_ll_set_clock(dev, clk) gpspi_flash_ll_set_clock((spi_dev_t*)dev, (gpspi_flash_ll_clock_reg_t*)clk)
#define spi_flash_ll_set_miso_bitlen(dev, bitlen) gpspi_flash_ll_set_miso_bitlen((spi_dev_t*)dev, bitlen)
#define spi_flash_ll_set_mosi_bitlen(dev, bitlen) gpspi_flash_ll_set_mosi_bitlen((spi_dev_t*)dev, bitlen)
#define spi_flash_ll_set_command(dev, cmd, bitlen) gpspi_flash_ll_set_command((spi_dev_t*)dev, cmd, bitlen)
#define spi_flash_ll_set_addr_bitlen(dev, bitlen) gpspi_flash_ll_set_addr_bitlen((spi_dev_t*)dev, bitlen)
#define spi_flash_ll_get_addr_bitlen(dev) gpspi_flash_ll_get_addr_bitlen((spi_dev_t*)dev)
#define spi_flash_ll_set_address(dev, addr) gpspi_flash_ll_set_address((spi_dev_t*)dev, addr)
#define spi_flash_ll_set_usr_address(dev, addr, bitlen) gpspi_flash_ll_set_usr_address((spi_dev_t*)dev, addr, bitlen)
#define spi_flash_ll_set_dummy(dev, dummy) gpspi_flash_ll_set_dummy((spi_dev_t*)dev, dummy)
#define spi_flash_ll_set_dummy_out(dev, en, lev) gpspi_flash_ll_set_dummy_out((spi_dev_t*)dev, en, lev)
#define spi_flash_ll_set_hold(dev, hold_n) gpspi_flash_ll_set_hold((spi_dev_t*)dev, hold_n)
#define spi_flash_ll_set_cs_setup(dev, cs_setup_time) gpspi_flash_ll_set_cs_setup((spi_dev_t*)dev, cs_setup_time)
#else
#define spi_flash_ll_reset(dev) spimem_flash_ll_reset((spi_mem_dev_t*)dev)
#define spi_flash_ll_cmd_is_done(dev) spimem_flash_ll_cmd_is_done((spi_mem_dev_t*)dev)
#define spi_flash_ll_erase_chip(dev) spimem_flash_ll_erase_chip((spi_mem_dev_t*)dev)
#define spi_flash_ll_erase_sector(dev) spimem_flash_ll_erase_sector((spi_mem_dev_t*)dev)
#define spi_flash_ll_erase_block(dev) spimem_flash_ll_erase_block((spi_mem_dev_t*)dev)
#define spi_flash_ll_set_write_protect(dev, wp) spimem_flash_ll_set_write_protect((spi_mem_dev_t*)dev, wp)
#define spi_flash_ll_get_buffer_data(dev, buffer, read_len) spimem_flash_ll_get_buffer_data((spi_mem_dev_t*)dev, buffer, read_len)
#define spi_flash_ll_set_buffer_data(dev, buffer, len) spimem_flash_ll_set_buffer_data((spi_mem_dev_t*)dev, buffer, len)
#define spi_flash_ll_program_page(dev, buffer, len) spimem_flash_ll_program_page((spi_mem_dev_t*)dev, buffer, len)
#define spi_flash_ll_user_start(dev) spimem_flash_ll_user_start((spi_mem_dev_t*)dev)
#define spi_flash_ll_host_idle(dev) spimem_flash_ll_host_idle((spi_mem_dev_t*)dev)
#define spi_flash_ll_read_phase(dev) spimem_flash_ll_read_phase((spi_mem_dev_t*)dev)
#define spi_flash_ll_set_cs_pin(dev, pin) spimem_flash_ll_set_cs_pin((spi_mem_dev_t*)dev, pin)
#define spi_flash_ll_set_read_mode(dev, read_mode) spimem_flash_ll_set_read_mode((spi_mem_dev_t*)dev, read_mode)
#define spi_flash_ll_set_clock(dev, clk) spimem_flash_ll_set_clock((spi_mem_dev_t*)dev, (spimem_flash_ll_clock_reg_t*)clk)
#define spi_flash_ll_set_miso_bitlen(dev, bitlen) spimem_flash_ll_set_miso_bitlen((spi_mem_dev_t*)dev, bitlen)
#define spi_flash_ll_set_mosi_bitlen(dev, bitlen) spimem_flash_ll_set_mosi_bitlen((spi_mem_dev_t*)dev, bitlen)
#define spi_flash_ll_set_command(dev, cmd, bitlen) spimem_flash_ll_set_command((spi_mem_dev_t*)dev, cmd, bitlen)
#define spi_flash_ll_set_addr_bitlen(dev, bitlen) spimem_flash_ll_set_addr_bitlen((spi_mem_dev_t*)dev, bitlen)
#define spi_flash_ll_get_addr_bitlen(dev) spimem_flash_ll_get_addr_bitlen((spi_mem_dev_t*) dev)
#define spi_flash_ll_set_address(dev, addr) spimem_flash_ll_set_address((spi_mem_dev_t*)dev, addr)
#define spi_flash_ll_set_usr_address(dev, addr, bitlen) spimem_flash_ll_set_usr_address((spi_mem_dev_t*)dev, addr, bitlen)
#define spi_flash_ll_set_dummy(dev, dummy) spimem_flash_ll_set_dummy((spi_mem_dev_t*)dev, dummy)
#define spi_flash_ll_set_dummy_out(dev, en, lev) spimem_flash_ll_set_dummy_out((spi_mem_dev_t*)dev, en, lev)
#define spi_flash_ll_set_hold(dev, hold_n) spimem_flash_ll_set_hold((spi_mem_dev_t*)dev, hold_n)
#define spi_flash_ll_set_cs_setup(dev, cs_setup_time) spimem_flash_ll_set_cs_setup((spi_mem_dev_t*)dev, cs_setup_time)
#endif
#ifdef __cplusplus
}
#endif

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,560 @@
// 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.
/*******************************************************************************
* NOTICE
* The ll is not public api, don't use in application code.
* See readme.md in soc/include/hal/readme.md
******************************************************************************/
// The Lowlevel layer for SPI Flash
#pragma once
#include <stdlib.h>
#include <sys/param.h> // For MIN/MAX
#include <stdbool.h>
#include <string.h>
#include "soc/spi_periph.h"
#include "hal/spi_types.h"
#include "hal/spi_flash_types.h"
#ifdef __cplusplus
extern "C" {
#endif
#define spimem_flash_ll_get_hw(host_id) (((host_id)==SPI1_HOST ? &SPIMEM1 : NULL ))
#define spimem_flash_ll_hw_get_id(dev) ((dev) == (void*)&SPIMEM1? SPI1_HOST: -1)
typedef typeof(SPIMEM1.clock) spimem_flash_ll_clock_reg_t;
//Supported clock register values
#define SPIMEM_FLASH_LL_CLKREG_VAL_5MHZ ((spimem_flash_ll_clock_reg_t){.val=0x000F070F}) ///< Clock set to 5 MHz
#define SPIMEM_FLASH_LL_CLKREG_VAL_10MHZ ((spimem_flash_ll_clock_reg_t){.val=0x00070307}) ///< Clock set to 10 MHz
#define SPIMEM_FLASH_LL_CLKREG_VAL_20MHZ ((spimem_flash_ll_clock_reg_t){.val=0x00030103}) ///< Clock set to 20 MHz
#define SPIMEM_FLASH_LL_CLKREG_VAL_26MHZ ((spimem_flash_ll_clock_reg_t){.val=0x00020002}) ///< Clock set to 26 MHz
#define SPIMEM_FLASH_LL_CLKREG_VAL_40MHZ ((spimem_flash_ll_clock_reg_t){.val=0x00010001}) ///< Clock set to 40 MHz
#define SPIMEM_FLASH_LL_CLKREG_VAL_80MHZ ((spimem_flash_ll_clock_reg_t){.val=0x80000000}) ///< Clock set to 80 MHz
/*------------------------------------------------------------------------------
* Control
*----------------------------------------------------------------------------*/
/**
* Reset peripheral registers before configuration and starting control
*
* @param dev Beginning address of the peripheral registers.
*/
static inline void spimem_flash_ll_reset(spi_mem_dev_t *dev)
{
dev->user.val = 0;
dev->ctrl.val = 0;
}
/**
* Check whether the previous operation is done.
*
* @param dev Beginning address of the peripheral registers.
*
* @return true if last command is done, otherwise false.
*/
static inline bool spimem_flash_ll_cmd_is_done(const spi_mem_dev_t *dev)
{
return (dev->cmd.val == 0);
}
/**
* Erase the flash chip.
*
* @param dev Beginning address of the peripheral registers.
*/
static inline void spimem_flash_ll_erase_chip(spi_mem_dev_t *dev)
{
dev->cmd.flash_ce = 1;
}
/**
* Erase the sector, the address should be set by spimem_flash_ll_set_address.
*
* @param dev Beginning address of the peripheral registers.
*/
static inline void spimem_flash_ll_erase_sector(spi_mem_dev_t *dev)
{
dev->ctrl.val = 0;
dev->cmd.flash_se = 1;
}
/**
* Erase the block, the address should be set by spimem_flash_ll_set_address.
*
* @param dev Beginning address of the peripheral registers.
*/
static inline void spimem_flash_ll_erase_block(spi_mem_dev_t *dev)
{
dev->cmd.flash_be = 1;
}
/**
* Suspend erase/program operation.
*
* @param dev Beginning address of the peripheral registers.
*/
static inline void spimem_flash_ll_suspend(spi_mem_dev_t *dev)
{
dev->flash_sus_ctrl.flash_pes = 1;
}
/**
* Resume suspended erase/program operation.
*
* @param dev Beginning address of the peripheral registers.
*/
static inline void spimem_flash_ll_resume(spi_mem_dev_t *dev)
{
dev->flash_sus_ctrl.flash_per = 1;
}
/**
* Initialize auto suspend mode, and esp32c3 doesn't support disable auto-suspend.
*
* @param dev Beginning address of the peripheral registers.
* @param auto_sus Enable/disable Flash Auto-Suspend.
*/
static inline void spimem_flash_ll_auto_suspend_init(spi_mem_dev_t *dev, bool auto_sus)
{
dev->flash_sus_ctrl.flash_pes_en = auto_sus;
}
/**
* Initialize auto resume mode
*
* @param dev Beginning address of the peripheral registers.
* @param auto_res Enable/Disable Flash Auto-Resume.
*
*/
static inline void spimem_flash_ll_auto_resume_init(spi_mem_dev_t *dev, bool auto_res)
{
dev->flash_sus_ctrl.pes_per_en = auto_res;
}
/**
* Setup the flash suspend command, may vary from chips to chips.
*
* @param dev Beginning address of the peripheral registers.
* @param sus_cmd Flash suspend command.
*
*/
static inline void spimem_flash_ll_suspend_cmd_setup(spi_mem_dev_t *dev, uint32_t sus_cmd)
{
dev->flash_sus_cmd.flash_pes_command = sus_cmd;
}
/**
* Setup the flash resume command, may vary from chips to chips.
*
* @param dev Beginning address of the peripheral registers.
* @param res_cmd Flash resume command.
*
*/
static inline void spimem_flash_ll_resume_cmd_setup(spi_mem_dev_t *dev, uint32_t res_cmd)
{
dev->flash_sus_cmd.flash_per_command = res_cmd;
}
/**
* Setup the flash read suspend status command, may vary from chips to chips.
*
* @param dev Beginning address of the peripheral registers.
* @param pesr_cmd Flash read suspend status command.
*
*/
static inline void spimem_flash_ll_rd_sus_cmd_setup(spi_mem_dev_t *dev, uint32_t pesr_cmd)
{
dev->flash_sus_cmd.wait_pesr_command = pesr_cmd;
}
/**
* Setup to check SUS/SUS1/SUS2 to ensure the suspend status of flashs.
*
* @param dev Beginning address of the peripheral registers.
* @param sus_check_sus_en 1: enable, 0: disable.
*
*/
static inline void spimem_flash_ll_sus_check_sus_setup(spi_mem_dev_t *dev, bool sus_check_sus_en)
{
dev->flash_sus_ctrl.sus_timeout_cnt = 5;
dev->flash_sus_ctrl.pes_end_en = sus_check_sus_en;
}
/**
* Setup to check SUS/SUS1/SUS2 to ensure the resume status of flashs.
*
* @param dev Beginning address of the peripheral registers.
* @param sus_check_sus_en 1: enable, 0: disable.
*
*/
static inline void spimem_flash_ll_res_check_sus_setup(spi_mem_dev_t *dev, bool res_check_sus_en)
{
dev->flash_sus_ctrl.sus_timeout_cnt = 5;
dev->flash_sus_ctrl.per_end_en = res_check_sus_en;
}
/**
* Set 8 bit command to read suspend status
*
* @param dev Beginning address of the peripheral registers.
*/
static inline void spimem_flash_ll_set_read_sus_status(spi_mem_dev_t *dev, uint32_t sus_conf)
{
dev->flash_sus_ctrl.frd_sus_2b = 0;
dev->flash_sus_ctrl.pesr_end_msk = sus_conf;
}
/**
* Initialize auto wait idle mode
*
* @param dev Beginning address of the peripheral registers.
* @param auto_waiti Enable/disable auto wait-idle function
*/
static inline void spimem_flash_ll_auto_wait_idle_init(spi_mem_dev_t *dev, bool auto_waiti)
{
dev->flash_waiti_ctrl.waiti_cmd = 0x05;
dev->flash_sus_ctrl.flash_per_wait_en = auto_waiti;
dev->flash_sus_ctrl.flash_pes_wait_en = auto_waiti;
}
/**
* Return the suspend status of erase or program operations.
*
* @param dev Beginning address of the peripheral registers.
*
* @return true if suspended, otherwise false.
*/
static inline bool spimem_flash_ll_sus_status(spi_mem_dev_t *dev)
{
return dev->sus_status.flash_sus;
}
/**
* Enable/disable write protection for the flash chip.
*
* @param dev Beginning address of the peripheral registers.
* @param wp true to enable the protection, false to disable (write enable).
*/
static inline void spimem_flash_ll_set_write_protect(spi_mem_dev_t *dev, bool wp)
{
if (wp) {
dev->cmd.flash_wrdi = 1;
} else {
dev->cmd.flash_wren = 1;
}
}
/**
* Get the read data from the buffer after ``spimem_flash_ll_read`` is done.
*
* @param dev Beginning address of the peripheral registers.
* @param buffer Buffer to hold the output data
* @param read_len Length to get out of the buffer
*/
static inline void spimem_flash_ll_get_buffer_data(spi_mem_dev_t *dev, void *buffer, uint32_t read_len)
{
if (((intptr_t)buffer % 4 == 0) && (read_len % 4 == 0)) {
// If everything is word-aligned, do a faster memcpy
memcpy(buffer, (void *)dev->data_buf, read_len);
} else {
// Otherwise, slow(er) path copies word by word
int copy_len = read_len;
for (int i = 0; i < (read_len + 3) / 4; i++) {
int word_len = MIN(sizeof(uint32_t), copy_len);
uint32_t word = dev->data_buf[i];
memcpy(buffer, &word, word_len);
buffer = (void *)((intptr_t)buffer + word_len);
copy_len -= word_len;
}
}
}
/**
* Set the data to be written in the data buffer.
*
* @param dev Beginning address of the peripheral registers.
* @param buffer Buffer holding the data
* @param length Length of data in bytes.
*/
static inline void spimem_flash_ll_set_buffer_data(spi_mem_dev_t *dev, const void *buffer, uint32_t length)
{
// Load data registers, word at a time
int num_words = (length + 3) / 4;
for (int i = 0; i < num_words; i++) {
uint32_t word = 0;
uint32_t word_len = MIN(length, sizeof(word));
memcpy(&word, buffer, word_len);
dev->data_buf[i] = word;
length -= word_len;
buffer = (void *)((intptr_t)buffer + word_len);
}
}
/**
* Program a page of the flash chip. Call ``spimem_flash_ll_set_address`` before
* this to set the address to program.
*
* @param dev Beginning address of the peripheral registers.
* @param buffer Buffer holding the data to program
* @param length Length to program.
*/
static inline void spimem_flash_ll_program_page(spi_mem_dev_t *dev, const void *buffer, uint32_t length)
{
dev->user.usr_dummy = 0;
spimem_flash_ll_set_buffer_data(dev, buffer, length);
dev->cmd.flash_pp = 1;
}
/**
* Trigger a user defined transaction. All phases, including command, address, dummy, and the data phases,
* should be configured before this is called.
*
* @param dev Beginning address of the peripheral registers.
*/
static inline void spimem_flash_ll_user_start(spi_mem_dev_t *dev)
{
dev->cmd.usr = 1;
}
/**
* Check whether the host is idle to perform new commands.
*
* @param dev Beginning address of the peripheral registers.
*
* @return true if the host is idle, otherwise false
*/
static inline bool spimem_flash_ll_host_idle(const spi_mem_dev_t *dev)
{
return dev->fsm.spi0_mst_st == 0;
}
/**
* Set phases for user-defined transaction to read
*
* @param dev Beginning address of the peripheral registers.
*/
static inline void spimem_flash_ll_read_phase(spi_mem_dev_t *dev)
{
typeof (dev->user) user = {
.usr_command = 1,
.usr_mosi = 0,
.usr_miso = 1,
.usr_addr = 1,
};
dev->user = user;
}
/*------------------------------------------------------------------------------
* Configs
*----------------------------------------------------------------------------*/
/**
* Select which pin to use for the flash
*
* @param dev Beginning address of the peripheral registers.
* @param pin Pin ID to use, 0-2. Set to other values to disable all the CS pins.
*/
static inline void spimem_flash_ll_set_cs_pin(spi_mem_dev_t *dev, int pin)
{
dev->misc.cs0_dis = (pin == 0) ? 0 : 1;
dev->misc.cs1_dis = (pin == 1) ? 0 : 1;
}
/**
* Set the read io mode.
*
* @param dev Beginning address of the peripheral registers.
* @param read_mode I/O mode to use in the following transactions.
*/
static inline void spimem_flash_ll_set_read_mode(spi_mem_dev_t *dev, esp_flash_io_mode_t read_mode)
{
typeof (dev->ctrl) ctrl = dev->ctrl;
ctrl.val &= ~(SPI_MEM_FREAD_QIO_M | SPI_MEM_FREAD_QUAD_M | SPI_MEM_FREAD_DIO_M | SPI_MEM_FREAD_DUAL_M);
ctrl.val |= SPI_MEM_FASTRD_MODE_M;
switch (read_mode) {
case SPI_FLASH_FASTRD:
//the default option
break;
case SPI_FLASH_QIO:
ctrl.fread_qio = 1;
break;
case SPI_FLASH_QOUT:
ctrl.fread_quad = 1;
break;
case SPI_FLASH_DIO:
ctrl.fread_dio = 1;
break;
case SPI_FLASH_DOUT:
ctrl.fread_dual = 1;
break;
case SPI_FLASH_SLOWRD:
ctrl.fastrd_mode = 0;
break;
default:
abort();
}
dev->ctrl = ctrl;
}
/**
* Set clock frequency to work at.
*
* @param dev Beginning address of the peripheral registers.
* @param clock_val pointer to the clock value to set
*/
static inline void spimem_flash_ll_set_clock(spi_mem_dev_t *dev, spimem_flash_ll_clock_reg_t *clock_val)
{
dev->clock = *clock_val;
}
/**
* Set the input length, in bits.
*
* @param dev Beginning address of the peripheral registers.
* @param bitlen Length of input, in bits.
*/
static inline void spimem_flash_ll_set_miso_bitlen(spi_mem_dev_t *dev, uint32_t bitlen)
{
dev->user.usr_miso = bitlen > 0;
dev->miso_dlen.usr_miso_bit_len = bitlen ? (bitlen - 1) : 0;
}
/**
* Set the output length, in bits (not including command, address and dummy
* phases)
*
* @param dev Beginning address of the peripheral registers.
* @param bitlen Length of output, in bits.
*/
static inline void spimem_flash_ll_set_mosi_bitlen(spi_mem_dev_t *dev, uint32_t bitlen)
{
dev->user.usr_mosi = bitlen > 0;
dev->mosi_dlen.usr_mosi_bit_len = bitlen ? (bitlen - 1) : 0;
}
/**
* Set the command.
*
* @param dev Beginning address of the peripheral registers.
* @param command Command to send
* @param bitlen Length of the command
*/
static inline void spimem_flash_ll_set_command(spi_mem_dev_t *dev, uint32_t command, uint32_t bitlen)
{
dev->user.usr_command = 1;
typeof(dev->user2) user2 = {
.usr_command_value = command,
.usr_command_bitlen = (bitlen - 1),
};
dev->user2 = user2;
}
/**
* Get the address length that is set in register, in bits.
*
* @param dev Beginning address of the peripheral registers.
*
*/
static inline int spimem_flash_ll_get_addr_bitlen(spi_mem_dev_t *dev)
{
return dev->user.usr_addr ? dev->user1.usr_addr_bitlen + 1 : 0;
}
/**
* Set the address length to send, in bits. Should be called before commands that requires the address e.g. erase sector, read, write...
*
* @param dev Beginning address of the peripheral registers.
* @param bitlen Length of the address, in bits
*/
static inline void spimem_flash_ll_set_addr_bitlen(spi_mem_dev_t *dev, uint32_t bitlen)
{
dev->user1.usr_addr_bitlen = (bitlen - 1);
dev->user.usr_addr = bitlen ? 1 : 0;
}
/**
* Set the address to send. Should be called before commands that requires the address e.g. erase sector, read, write...
*
* @param dev Beginning address of the peripheral registers.
* @param addr Address to send
*/
static inline void spimem_flash_ll_set_address(spi_mem_dev_t *dev, uint32_t addr)
{
dev->addr = addr;
}
/**
* Set the address to send in user mode. Should be called before commands that requires the address e.g. erase sector, read, write...
*
* @param dev Beginning address of the peripheral registers.
* @param addr Address to send
*/
static inline void spimem_flash_ll_set_usr_address(spi_mem_dev_t *dev, uint32_t addr, uint32_t bitlen)
{
(void)bitlen;
spimem_flash_ll_set_address(dev, addr);
}
/**
* Set the length of dummy cycles.
*
* @param dev Beginning address of the peripheral registers.
* @param dummy_n Cycles of dummy phases
*/
static inline void spimem_flash_ll_set_dummy(spi_mem_dev_t *dev, uint32_t dummy_n)
{
dev->user.usr_dummy = dummy_n ? 1 : 0;
dev->user1.usr_dummy_cyclelen = dummy_n - 1;
}
/**
* Set D/Q output level during dummy phase
*
* @param dev Beginning address of the peripheral registers.
* @param out_en whether to enable IO output for dummy phase
* @param out_level dummy output level
*/
static inline void spimem_flash_ll_set_dummy_out(spi_mem_dev_t *dev, uint32_t out_en, uint32_t out_lev)
{
dev->ctrl.fdummy_out = out_en;
dev->ctrl.q_pol = out_lev;
dev->ctrl.d_pol = out_lev;
}
/**
* Set CS hold time.
*
* @param dev Beginning address of the peripheral registers.
* @param hold_n CS hold time config used by the host.
*/
static inline void spimem_flash_ll_set_hold(spi_mem_dev_t *dev, uint32_t hold_n)
{
dev->ctrl2.cs_hold_time = hold_n - 1;
dev->user.cs_hold = (hold_n > 0? 1: 0);
}
static inline void spimem_flash_ll_set_cs_setup(spi_mem_dev_t *dev, uint32_t cs_setup_time)
{
dev->user.cs_setup = (cs_setup_time > 0 ? 1 : 0);
dev->ctrl2.cs_setup_time = cs_setup_time - 1;
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,164 @@
// 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 <assert.h>
#include "soc/systimer_struct.h"
#define SYSTIMER_LL_COUNTER_CLOCK (0) // Counter used for "wallclock" time
#define SYSTIMER_LL_COUNTER_OS_TICK (1) // Counter used for OS tick
#define SYSTIMER_LL_ALARM_OS_TICK_CORE0 (0) // Alarm used for OS tick of CPU core 0
#define SYSTIMER_LL_ALARM_CLOCK (2) // Alarm used for "wallclock" time
#define SYSTIMER_LL_TICKS_PER_US (16) // 16 systimer ticks == 1us
#ifdef __cplusplus
extern "C" {
#endif
// All these functions get invoked either from ISR or HAL that linked to IRAM.
// Always inline these functions even no gcc optimization is applied.
/******************* Clock *************************/
__attribute__((always_inline)) static inline void systimer_ll_enable_clock(systimer_dev_t *dev, bool en)
{
dev->conf.clk_en = en;
}
/******************* Counter *************************/
__attribute__((always_inline)) static inline void systimer_ll_enable_counter(systimer_dev_t *dev, uint32_t counter_id, bool en)
{
if (en) {
dev->conf.val |= 1 << (30 - counter_id);
} else {
dev->conf.val &= ~(1 << (30 - counter_id));
}
}
__attribute__((always_inline)) static inline void systimer_ll_counter_can_stall_by_cpu(systimer_dev_t *dev, uint32_t counter_id, uint32_t cpu_id, bool can)
{
if (can) {
dev->conf.val |= 1 << ((28 - counter_id * 2) - cpu_id);
} else {
dev->conf.val &= ~(1 << ((28 - counter_id * 2) - cpu_id));
}
}
__attribute__((always_inline)) static inline void systimer_ll_counter_snapshot(systimer_dev_t *dev, uint32_t counter_id)
{
dev->unit_op[counter_id].timer_unit_update = 1;
}
__attribute__((always_inline)) static inline bool systimer_ll_is_counter_value_valid(systimer_dev_t *dev, uint32_t counter_id)
{
return dev->unit_op[counter_id].timer_unit_value_valid;
}
__attribute__((always_inline)) static inline void systimer_ll_set_counter_value(systimer_dev_t *dev, uint32_t counter_id, uint64_t value)
{
dev->unit_load_val[counter_id].hi.timer_unit_load_hi = value >> 32;
dev->unit_load_val[counter_id].lo.timer_unit_load_lo = value & 0xFFFFFFFF;
}
__attribute__((always_inline)) static inline uint32_t systimer_ll_get_counter_value_low(systimer_dev_t *dev, uint32_t counter_id)
{
return dev->unit_val[counter_id].lo.timer_unit_value_lo;
}
__attribute__((always_inline)) static inline uint32_t systimer_ll_get_counter_value_high(systimer_dev_t *dev, uint32_t counter_id)
{
return dev->unit_val[counter_id].hi.timer_unit_value_hi;
}
__attribute__((always_inline)) static inline void systimer_ll_apply_counter_value(systimer_dev_t *dev, uint32_t counter_id)
{
dev->unit_load[counter_id].val = 0x01;
}
/******************* Alarm *************************/
__attribute__((always_inline)) static inline void systimer_ll_set_alarm_target(systimer_dev_t *dev, uint32_t alarm_id, uint64_t value)
{
dev->target_val[alarm_id].hi.timer_target_hi = value >> 32;
dev->target_val[alarm_id].lo.timer_target_lo = value & 0xFFFFFFFF;
}
__attribute__((always_inline)) static inline uint64_t systimer_ll_get_alarm_target(systimer_dev_t *dev, uint32_t alarm_id)
{
return ((uint64_t)(dev->target_val[alarm_id].hi.timer_target_hi) << 32) | dev->target_val[alarm_id].lo.timer_target_lo;
}
__attribute__((always_inline)) static inline void systimer_ll_connect_alarm_counter(systimer_dev_t *dev, uint32_t alarm_id, uint32_t counter_id)
{
dev->target_conf[alarm_id].target_timer_unit_sel = counter_id;
}
__attribute__((always_inline)) static inline void systimer_ll_enable_alarm_oneshot(systimer_dev_t *dev, uint32_t alarm_id)
{
dev->target_conf[alarm_id].target_period_mode = 0;
}
__attribute__((always_inline)) static inline void systimer_ll_enable_alarm_period(systimer_dev_t *dev, uint32_t alarm_id)
{
dev->target_conf[alarm_id].target_period_mode = 1;
}
__attribute__((always_inline)) static inline void systimer_ll_set_alarm_period(systimer_dev_t *dev, uint32_t alarm_id, uint32_t period)
{
assert(period < (1 << 26));
dev->target_conf[alarm_id].target_period = period;
}
__attribute__((always_inline)) static inline void systimer_ll_apply_alarm_value(systimer_dev_t *dev, uint32_t alarm_id)
{
dev->comp_load[alarm_id].val = 0x01;
}
__attribute__((always_inline)) static inline void systimer_ll_enable_alarm(systimer_dev_t *dev, uint32_t alarm_id, bool en)
{
if (en) {
dev->conf.val |= 1 << (24 - alarm_id);
} else {
dev->conf.val &= ~(1 << (24 - alarm_id));
}
}
/******************* Interrupt *************************/
__attribute__((always_inline)) static inline void systimer_ll_enable_alarm_int(systimer_dev_t *dev, uint32_t alarm_id, bool en)
{
if (en) {
dev->int_ena.val |= 1 << alarm_id;
} else {
dev->int_ena.val &= ~(1 << alarm_id);
}
}
__attribute__((always_inline)) static inline bool systimer_ll_is_alarm_int_fired(systimer_dev_t *dev, uint32_t alarm_id)
{
return dev->int_st.val & (1 << alarm_id);
}
__attribute__((always_inline)) static inline void systimer_ll_clear_alarm_int(systimer_dev_t *dev, uint32_t alarm_id)
{
dev->int_clr.val |= 1 << alarm_id;
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,430 @@
// 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.
// The LL layer for Timer Group register operations.
// Note that most of the register operations in this layer are non-atomic operations.
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include <stdlib.h>
#include "hal/timer_types.h"
#include "soc/timer_periph.h"
_Static_assert(TIMER_INTR_T0 == TIMG_T0_INT_CLR, "Add mapping to LL interrupt handling, since it's no longer naturally compatible with the timer_intr_t");
_Static_assert(TIMER_INTR_WDT == TIMG_WDT_INT_CLR, "Add mapping to LL interrupt handling, since it's no longer naturally compatible with the timer_intr_t");
typedef struct {
timg_dev_t *dev;
timer_idx_t idx;
} timer_ll_context_t;
// Get timer group instance with giving group number
#define TIMER_LL_GET_HW(num) ((num == 0) ? (&TIMERG0) : (&TIMERG1))
/**
* @brief Set timer clock prescale value
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
* @param divider Prescale value
*
* @return None
*/
static inline void timer_ll_set_divider(timg_dev_t *hw, timer_idx_t timer_num, uint32_t divider)
{
assert(divider >= 2 && divider <= 65536);
if (divider >= 65536) {
divider = 0;
}
int timer_en = hw->hw_timer[timer_num].config.enable;
hw->hw_timer[timer_num].config.enable = 0;
hw->hw_timer[timer_num].config.divcnt_rst = 1;
hw->hw_timer[timer_num].config.divider = divider;
hw->hw_timer[timer_num].config.enable = timer_en;
}
/**
* @brief Get timer clock prescale value
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
* @param divider Pointer to accept the prescale value
*
* @return None
*/
static inline void timer_ll_get_divider(timg_dev_t *hw, timer_idx_t timer_num, uint32_t *divider)
{
uint32_t d = hw->hw_timer[timer_num].config.divider;
if (d == 0) {
d = 65536;
} else if (d == 1) {
d = 2;
}
*divider = d;
}
/**
* @brief Load counter value into time-base counter
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
* @param load_val Counter value
*
* @return None
*/
static inline void timer_ll_set_counter_value(timg_dev_t *hw, timer_idx_t timer_num, uint64_t load_val)
{
hw->hw_timer[timer_num].load_high.load_hi = (uint32_t) (load_val >> 32);
hw->hw_timer[timer_num].load_low = (uint32_t) load_val;
hw->hw_timer[timer_num].reload = 1;
}
/**
* @brief Get counter value from time-base counter
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
* @param timer_val Pointer to accept the counter value
*
* @return None
*/
FORCE_INLINE_ATTR void timer_ll_get_counter_value(timg_dev_t *hw, timer_idx_t timer_num, uint64_t *timer_val)
{
hw->hw_timer[timer_num].update.update = 1;
while (hw->hw_timer[timer_num].update.update) {}
*timer_val = ((uint64_t) hw->hw_timer[timer_num].cnt_high.hi << 32) | (hw->hw_timer[timer_num].cnt_low);
}
/**
* @brief Set counter mode, include increment mode and decrement mode.
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
* @param increase_en True to increment mode, fasle to decrement mode
*
* @return None
*/
static inline void timer_ll_set_counter_increase(timg_dev_t *hw, timer_idx_t timer_num, bool increase_en)
{
hw->hw_timer[timer_num].config.increase = increase_en;
}
/**
* @brief Get counter mode, include increment mode and decrement mode.
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
*
* @return
* - true Increment mode
* - false Decrement mode
*/
static inline bool timer_ll_get_counter_increase(timg_dev_t *hw, timer_idx_t timer_num)
{
return hw->hw_timer[timer_num].config.increase;
}
/**
* @brief Set counter status, enable or disable counter.
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
* @param counter_en True to enable counter, false to disable counter
*
* @return None
*/
FORCE_INLINE_ATTR void timer_ll_set_counter_enable(timg_dev_t *hw, timer_idx_t timer_num, bool counter_en)
{
hw->hw_timer[timer_num].config.enable = counter_en;
}
/**
* @brief Get counter status.
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
*
* @return
* - true Enable counter
* - false Disable conuter
*/
static inline bool timer_ll_get_counter_enable(timg_dev_t *hw, timer_idx_t timer_num)
{
return hw->hw_timer[timer_num].config.enable;
}
/**
* @brief Set auto reload mode.
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
* @param auto_reload_en True to enable auto reload mode, flase to disable auto reload mode
*
* @return None
*/
static inline void timer_ll_set_auto_reload(timg_dev_t *hw, timer_idx_t timer_num, bool auto_reload_en)
{
hw->hw_timer[timer_num].config.autoreload = auto_reload_en;
}
/**
* @brief Get auto reload mode.
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
*
* @return
* - true Enable auto reload mode
* - false Disable auto reload mode
*/
FORCE_INLINE_ATTR bool timer_ll_get_auto_reload(timg_dev_t *hw, timer_idx_t timer_num)
{
return hw->hw_timer[timer_num].config.autoreload;
}
/**
* @brief Set the counter value to trigger the alarm.
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
* @param alarm_value Counter value to trigger the alarm
*
* @return None
*/
FORCE_INLINE_ATTR void timer_ll_set_alarm_value(timg_dev_t *hw, timer_idx_t timer_num, uint64_t alarm_value)
{
hw->hw_timer[timer_num].alarm_high.alarm_hi = (uint32_t) (alarm_value >> 32);
hw->hw_timer[timer_num].alarm_low = (uint32_t) alarm_value;
}
/**
* @brief Get the counter value to trigger the alarm.
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
* @param alarm_value Pointer to accept the counter value to trigger the alarm
*
* @return None
*/
static inline void timer_ll_get_alarm_value(timg_dev_t *hw, timer_idx_t timer_num, uint64_t *alarm_value)
{
*alarm_value = ((uint64_t) hw->hw_timer[timer_num].alarm_high.alarm_hi << 32) | (hw->hw_timer[timer_num].alarm_low);
}
/**
* @brief Set the alarm status, enable or disable the alarm.
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
* @param alarm_en True to enable alarm, false to disable alarm
*
* @return None
*/
FORCE_INLINE_ATTR void timer_ll_set_alarm_enable(timg_dev_t *hw, timer_idx_t timer_num, bool alarm_en)
{
hw->hw_timer[timer_num].config.alarm_en = alarm_en;
}
/**
* @brief Get the alarm status.
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
*
* @return
* - true Enable alarm
* - false Disable alarm
*/
static inline bool timer_ll_get_alarm_enable(timg_dev_t *hw, timer_idx_t timer_num)
{
return hw->hw_timer[timer_num].config.alarm_en;
}
/**
* @brief Enable timer interrupt.
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
*
* @return None
*/
FORCE_INLINE_ATTR void timer_ll_intr_enable(timg_dev_t *hw, timer_idx_t timer_num)
{
hw->int_ena.val |= BIT(timer_num);
}
/**
* @brief Disable timer interrupt.
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
*
* @return None
*/
FORCE_INLINE_ATTR void timer_ll_intr_disable(timg_dev_t *hw, timer_idx_t timer_num)
{
hw->int_ena.val &= (~BIT(timer_num));
}
/**
* @brief Disable timer interrupt.
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
*
* @return None
*/
FORCE_INLINE_ATTR void timer_ll_clear_intr_status(timg_dev_t *hw, timer_idx_t timer_num)
{
hw->int_clr.val |= BIT(timer_num);
}
/**
* @brief Get interrupt status.
*
* @param hw Beginning address of the peripheral registers.
* @param intr_status Interrupt status
*
* @return None
*/
FORCE_INLINE_ATTR void timer_ll_get_intr_status(timg_dev_t *hw, uint32_t *intr_status)
{
*intr_status = hw->int_st.val & 0x01;
}
/**
* @brief Get interrupt raw status.
*
* @param group_num Timer group number, 0 for TIMERG0 or 1 for TIMERG1
* @param intr_raw_status Interrupt raw status
*
* @return None
*/
FORCE_INLINE_ATTR void timer_ll_get_intr_raw_status(timer_group_t group_num, uint32_t *intr_raw_status)
{
timg_dev_t *hw = TIMER_LL_GET_HW(group_num);
*intr_raw_status = hw->int_raw.val & 0x01;
}
/**
* @brief Set the level interrupt status, enable or disable the level interrupt.
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
* @param level_int_en True to enable level interrupt, false to disable level interrupt
*
* @return None
*/
static inline void timer_ll_set_level_int_enable(timg_dev_t *hw, timer_idx_t timer_num, bool level_int_en)
{
// Only "level" interrupts are supported on this target
}
/**
* @brief Get the level interrupt status.
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
*
* @return
* - true Enable level interrupt
* - false Disable level interrupt
*/
static inline bool timer_ll_get_level_int_enable(timg_dev_t *hw, timer_idx_t timer_num)
{
// Only "level" interrupts are supported on this target
return true;
}
/**
* @brief Set the edge interrupt status, enable or disable the edge interrupt.
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
* @param edge_int_en True to enable edge interrupt, false to disable edge interrupt
*
* @return None
*/
static inline void timer_ll_set_edge_int_enable(timg_dev_t *hw, timer_idx_t timer_num, bool edge_int_en)
{
// edge interrupt is not supported on C3
}
/**
* @brief Get the edge interrupt status.
*
* @param hw Beginning address of the peripheral registers.
* @param timer_num The timer number
*
* @return
* - true Enable edge interrupt
* - false Disable edge interrupt
*/
static inline bool timer_ll_get_edge_int_enable(timg_dev_t *hw, timer_idx_t timer_num)
{
// edge interrupt is not supported on C3
return false;
}
/**
* @brief Get interrupt status register address.
*
* @param hw Beginning address of the peripheral registers.
*
* @return uint32_t Interrupt status register address
*/
static inline uint32_t timer_ll_get_intr_status_reg(timg_dev_t *hw)
{
return (uint32_t) & (hw->int_st.val);
}
static inline uint32_t timer_ll_get_intr_mask_bit(timg_dev_t *hw, timer_idx_t timer_num)
{
return (1U << timer_num);
}
/**
* @brief Set clock source.
*
* @param hal Context of the HAL layer
* @param use_xtal_en True to use XTAL clock, flase to use APB clock
*
* @return None
*/
static inline void timer_ll_set_use_xtal(timg_dev_t *hw, timer_idx_t timer_num, bool use_xtal_en)
{
hw->hw_timer[timer_num].config.use_xtal = use_xtal_en;
}
/**
* @brief Get clock source.
*
* @param hal Context of the HAL layer
*
* @return
* - true Use XTAL clock
* - false Use APB clock
*/
static inline bool timer_ll_get_use_xtal(timg_dev_t *hw, timer_idx_t timer_num)
{
return hw->hw_timer[timer_num].config.use_xtal;
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,667 @@
// Copyright 2021 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.
/*******************************************************************************
* NOTICE
* The ll is not public api, don't use in application code.
* See readme.md in hal/include/hal/readme.md
******************************************************************************/
// The Lowlevel layer for TWAI
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <stdbool.h>
#include "hal/twai_types.h"
#include "soc/twai_periph.h"
/* ------------------------- Defines and Typedefs --------------------------- */
#define TWAI_LL_STATUS_RBS (0x1 << 0) //Receive Buffer Status
#define TWAI_LL_STATUS_DOS (0x1 << 1) //Data Overrun Status
#define TWAI_LL_STATUS_TBS (0x1 << 2) //Transmit Buffer Status
#define TWAI_LL_STATUS_TCS (0x1 << 3) //Transmission Complete Status
#define TWAI_LL_STATUS_RS (0x1 << 4) //Receive Status
#define TWAI_LL_STATUS_TS (0x1 << 5) //Transmit Status
#define TWAI_LL_STATUS_ES (0x1 << 6) //Error Status
#define TWAI_LL_STATUS_BS (0x1 << 7) //Bus Status
#define TWAI_LL_STATUS_MS (0x1 << 8) //Miss Status
#define TWAI_LL_INTR_RI (0x1 << 0) //Receive Interrupt
#define TWAI_LL_INTR_TI (0x1 << 1) //Transmit Interrupt
#define TWAI_LL_INTR_EI (0x1 << 2) //Error Interrupt
//Data overrun interrupt not supported in SW due to HW peculiarities
#define TWAI_LL_INTR_EPI (0x1 << 5) //Error Passive Interrupt
#define TWAI_LL_INTR_ALI (0x1 << 6) //Arbitration Lost Interrupt
#define TWAI_LL_INTR_BEI (0x1 << 7) //Bus Error Interrupt
/*
* The following frame structure has an NEARLY identical bit field layout to
* each byte of the TX buffer. This allows for formatting and parsing frames to
* be done outside of time critical regions (i.e., ISRs). All the ISR needs to
* do is to copy byte by byte to/from the TX/RX buffer. The two reserved bits in
* TX buffer are used in the frame structure to store the self_reception and
* single_shot flags which in turn indicate the type of transmission to execute.
*/
typedef union {
struct {
struct {
uint8_t dlc: 4; //Data length code (0 to 8) of the frame
uint8_t self_reception: 1; //This frame should be transmitted using self reception command
uint8_t single_shot: 1; //This frame should be transmitted using single shot command
uint8_t rtr: 1; //This frame is a remote transmission request
uint8_t frame_format: 1; //Format of the frame (1 = extended, 0 = standard)
};
union {
struct {
uint8_t id[2]; //11 bit standard frame identifier
uint8_t data[8]; //Data bytes (0 to 8)
uint8_t reserved8[2];
} standard;
struct {
uint8_t id[4]; //29 bit extended frame identifier
uint8_t data[8]; //Data bytes (0 to 8)
} extended;
};
};
uint8_t bytes[13];
} __attribute__((packed)) twai_ll_frame_buffer_t;
_Static_assert(sizeof(twai_ll_frame_buffer_t) == 13, "TX/RX buffer type should be 13 bytes");
/* ---------------------------- Mode Register ------------------------------- */
/**
* @brief Enter reset mode
*
* When in reset mode, the TWAI controller is effectively disconnected from the
* TWAI bus and will not participate in any bus activates. Reset mode is required
* in order to write the majority of configuration registers.
*
* @param hw Start address of the TWAI registers
*
* @note Reset mode is automatically entered on BUS OFF condition
*/
static inline void twai_ll_enter_reset_mode(twai_dev_t *hw)
{
hw->mode_reg.rm = 1;
}
/**
* @brief Exit reset mode
*
* When not in reset mode, the TWAI controller will take part in bus activities
* (e.g., send/receive/acknowledge messages and error frames) depending on the
* operating mode.
*
* @param hw Start address of the TWAI registers
*
* @note Reset mode must be exit to initiate BUS OFF recovery
*/
static inline void twai_ll_exit_reset_mode(twai_dev_t *hw)
{
hw->mode_reg.rm = 0;
}
/**
* @brief Check if in reset mode
* @param hw Start address of the TWAI registers
* @return true if in reset mode
*/
static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
{
return hw->mode_reg.rm;
}
/**
* @brief Set operating mode of TWAI controller
*
* @param hw Start address of the TWAI registers
* @param mode Operating mode
*
* @note Must be called in reset mode
*/
static inline void twai_ll_set_mode(twai_dev_t *hw, twai_mode_t mode)
{
if (mode == TWAI_MODE_NORMAL) { //Normal Operating mode
hw->mode_reg.lom = 0;
hw->mode_reg.stm = 0;
} else if (mode == TWAI_MODE_NO_ACK) { //Self Test Mode (No Ack)
hw->mode_reg.lom = 0;
hw->mode_reg.stm = 1;
} else if (mode == TWAI_MODE_LISTEN_ONLY) { //Listen Only Mode
hw->mode_reg.lom = 1;
hw->mode_reg.stm = 0;
}
}
/* --------------------------- Command Register ----------------------------- */
/**
* @brief Set TX command
*
* Setting the TX command will cause the TWAI controller to attempt to transmit
* the frame stored in the TX buffer. The TX buffer will be occupied (i.e.,
* locked) until TX completes.
*
* @param hw Start address of the TWAI registers
*
* @note Transmit commands should be called last (i.e., after handling buffer
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
static inline void twai_ll_set_cmd_tx(twai_dev_t *hw)
{
hw->command_reg.tr = 1;
}
/**
* @brief Set single shot TX command
*
* Similar to setting TX command, but the TWAI controller will not automatically
* retry transmission upon an error (e.g., due to an acknowledgement error).
*
* @param hw Start address of the TWAI registers
*
* @note Transmit commands should be called last (i.e., after handling buffer
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
static inline void twai_ll_set_cmd_tx_single_shot(twai_dev_t *hw)
{
hw->command_reg.val = 0x03; //Set command_reg.tr and command_reg.at simultaneously for single shot transmittion request
}
/**
* @brief Aborts TX
*
* Frames awaiting TX will be aborted. Frames already being TX are not aborted.
* Transmission Complete Status bit is automatically set to 1.
* Similar to setting TX command, but the TWAI controller will not automatically
* retry transmission upon an error (e.g., due to acknowledge error).
*
* @param hw Start address of the TWAI registers
*
* @note Transmit commands should be called last (i.e., after handling buffer
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
static inline void twai_ll_set_cmd_abort_tx(twai_dev_t *hw)
{
hw->command_reg.at = 1;
}
/**
* @brief Release RX buffer
*
* Rotates RX buffer to the next frame in the RX FIFO.
*
* @param hw Start address of the TWAI registers
*/
static inline void twai_ll_set_cmd_release_rx_buffer(twai_dev_t *hw)
{
hw->command_reg.rrb = 1;
}
/**
* @brief Clear data overrun
*
* Clears the data overrun status bit
*
* @param hw Start address of the TWAI registers
*/
static inline void twai_ll_set_cmd_clear_data_overrun(twai_dev_t *hw)
{
hw->command_reg.cdo = 1;
}
/**
* @brief Set self reception single shot command
*
* Similar to setting TX command, but the TWAI controller also simultaneously
* receive the transmitted frame and is generally used for self testing
* purposes. The TWAI controller will not ACK the received message, so consider
* using the NO_ACK operating mode.
*
* @param hw Start address of the TWAI registers
*
* @note Transmit commands should be called last (i.e., after handling buffer
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
static inline void twai_ll_set_cmd_self_rx_request(twai_dev_t *hw)
{
hw->command_reg.srr = 1;
}
/**
* @brief Set self reception request command
*
* Similar to setting the self reception request, but the TWAI controller will
* not automatically retry transmission upon an error (e.g., due to and
* acknowledgement error).
*
* @param hw Start address of the TWAI registers
*
* @note Transmit commands should be called last (i.e., after handling buffer
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
static inline void twai_ll_set_cmd_self_rx_single_shot(twai_dev_t *hw)
{
hw->command_reg.val = 0x12; //Set command_reg.srr and command_reg.at simultaneously for single shot self reception request
}
/* --------------------------- Status Register ------------------------------ */
/**
* @brief Get all status bits
*
* @param hw Start address of the TWAI registers
* @return Status bits
*/
static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
{
return hw->status_reg.val;
}
/**
* @brief Check if RX FIFO overrun status bit is set
*
* @param hw Start address of the TWAI registers
* @return Overrun status bit
*/
static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
{
return hw->status_reg.dos;
}
/**
* @brief Check if previously TX was successful
*
* @param hw Start address of the TWAI registers
* @return Whether previous TX was successful
*/
static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
{
return hw->status_reg.tcs;
}
/* -------------------------- Interrupt Register ---------------------------- */
/**
* @brief Get currently set interrupts
*
* Reading the interrupt registers will automatically clear all interrupts
* except for the Receive Interrupt.
*
* @param hw Start address of the TWAI registers
* @return Bit mask of set interrupts
*/
static inline uint32_t twai_ll_get_and_clear_intrs(twai_dev_t *hw)
{
return hw->interrupt_reg.val;
}
/* ----------------------- Interrupt Enable Register ------------------------ */
/**
* @brief Set which interrupts are enabled
*
* @param hw Start address of the TWAI registers
* @param Bit mask of interrupts to enable
*
* @note Must be called in reset mode
*/
static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
{
hw->interrupt_enable_reg.val = intr_mask;
}
/* ------------------------ Bus Timing Registers --------------------------- */
/**
* @brief Set bus timing
*
* @param hw Start address of the TWAI registers
* @param brp Baud Rate Prescaler
* @param sjw Synchronization Jump Width
* @param tseg1 Timing Segment 1
* @param tseg2 Timing Segment 2
* @param triple_sampling Triple Sampling enable/disable
*
* @note Must be called in reset mode
* @note ESP32C3 brp can be any even number between 2 to 32768
*/
static inline void twai_ll_set_bus_timing(twai_dev_t *hw, uint32_t brp, uint32_t sjw, uint32_t tseg1, uint32_t tseg2, bool triple_sampling)
{
hw->bus_timing_0_reg.brp = (brp / 2) - 1;
hw->bus_timing_0_reg.sjw = sjw - 1;
hw->bus_timing_1_reg.tseg1 = tseg1 - 1;
hw->bus_timing_1_reg.tseg2 = tseg2 - 1;
hw->bus_timing_1_reg.sam = triple_sampling;
}
/* ----------------------------- ALC Register ------------------------------- */
/**
* @brief Clear Arbitration Lost Capture Register
*
* Reading the ALC register rearms the Arbitration Lost Interrupt
*
* @param hw Start address of the TWAI registers
*/
static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
{
(void)hw->arbitration_lost_captue_reg.val;
}
/* ----------------------------- ECC Register ------------------------------- */
/**
* @brief Clear Error Code Capture register
*
* Reading the ECC register rearms the Bus Error Interrupt
*
* @param hw Start address of the TWAI registers
*/
static inline void twai_ll_clear_err_code_cap(twai_dev_t *hw)
{
(void)hw->error_code_capture_reg.val;
}
/* ----------------------------- EWL Register ------------------------------- */
/**
* @brief Set Error Warning Limit
*
* @param hw Start address of the TWAI registers
* @param ewl Error Warning Limit
*
* @note Must be called in reset mode
*/
static inline void twai_ll_set_err_warn_lim(twai_dev_t *hw, uint32_t ewl)
{
hw->error_warning_limit_reg.ewl = ewl;
}
/**
* @brief Get Error Warning Limit
*
* @param hw Start address of the TWAI registers
* @return Error Warning Limit
*/
static inline uint32_t twai_ll_get_err_warn_lim(twai_dev_t *hw)
{
return hw->error_warning_limit_reg.val;
}
/* ------------------------ RX Error Count Register ------------------------- */
/**
* @brief Get RX Error Counter
*
* @param hw Start address of the TWAI registers
* @return REC value
*
* @note REC is not frozen in reset mode. Listen only mode will freeze it. A BUS
* OFF condition automatically sets the REC to 0.
*/
static inline uint32_t twai_ll_get_rec(twai_dev_t *hw)
{
return hw->rx_error_counter_reg.val;
}
/**
* @brief Set RX Error Counter
*
* @param hw Start address of the TWAI registers
* @param rec REC value
*
* @note Must be called in reset mode
*/
static inline void twai_ll_set_rec(twai_dev_t *hw, uint32_t rec)
{
hw->rx_error_counter_reg.rxerr = rec;
}
/* ------------------------ TX Error Count Register ------------------------- */
/**
* @brief Get TX Error Counter
*
* @param hw Start address of the TWAI registers
* @return TEC value
*
* @note A BUS OFF condition will automatically set this to 128
*/
static inline uint32_t twai_ll_get_tec(twai_dev_t *hw)
{
return hw->tx_error_counter_reg.val;
}
/**
* @brief Set TX Error Counter
*
* @param hw Start address of the TWAI registers
* @param tec TEC value
*
* @note Must be called in reset mode
*/
static inline void twai_ll_set_tec(twai_dev_t *hw, uint32_t tec)
{
hw->tx_error_counter_reg.txerr = tec;
}
/* ---------------------- Acceptance Filter Registers ----------------------- */
/**
* @brief Set Acceptance Filter
* @param hw Start address of the TWAI registers
* @param code Acceptance Code
* @param mask Acceptance Mask
* @param single_filter Whether to enable single filter mode
*
* @note Must be called in reset mode
*/
static inline void twai_ll_set_acc_filter(twai_dev_t* hw, uint32_t code, uint32_t mask, bool single_filter)
{
uint32_t code_swapped = __builtin_bswap32(code);
uint32_t mask_swapped = __builtin_bswap32(mask);
for (int i = 0; i < 4; i++) {
hw->acceptance_filter.acr[i].byte = ((code_swapped >> (i * 8)) & 0xFF);
hw->acceptance_filter.amr[i].byte = ((mask_swapped >> (i * 8)) & 0xFF);
}
hw->mode_reg.afm = single_filter;
}
/* ------------------------- TX/RX Buffer Registers ------------------------- */
/**
* @brief Copy a formatted TWAI frame into TX buffer for transmission
*
* @param hw Start address of the TWAI registers
* @param tx_frame Pointer to formatted frame
*
* @note Call twai_ll_format_frame_buffer() to format a frame
*/
static inline void twai_ll_set_tx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t *tx_frame)
{
//Copy formatted frame into TX buffer
for (int i = 0; i < 13; i++) {
hw->tx_rx_buffer[i].val = tx_frame->bytes[i];
}
}
/**
* @brief Copy a received frame from the RX buffer for parsing
*
* @param hw Start address of the TWAI registers
* @param rx_frame Pointer to store formatted frame
*
* @note Call twai_ll_prase_frame_buffer() to parse the formatted frame
*/
static inline void twai_ll_get_rx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t *rx_frame)
{
//Copy RX buffer registers into frame
for (int i = 0; i < 13; i++) {
rx_frame->bytes[i] = hw->tx_rx_buffer[i].byte;
}
}
/**
* @brief Format contents of a TWAI frame into layout of TX Buffer
*
* This function encodes a message into a frame structure. The frame structure
* has an identical layout to the TX buffer, allowing the frame structure to be
* directly copied into TX buffer.
*
* @param[in] 11bit or 29bit ID
* @param[in] dlc Data length code
* @param[in] data Pointer to an 8 byte array containing data. NULL if no data
* @param[in] format Type of TWAI frame
* @param[in] single_shot Frame will not be retransmitted on failure
* @param[in] self_rx Frame will also be simultaneously received
* @param[out] tx_frame Pointer to store formatted frame
*/
static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const uint8_t *data,
uint32_t flags, twai_ll_frame_buffer_t *tx_frame)
{
bool is_extd = flags & TWAI_MSG_FLAG_EXTD;
bool is_rtr = flags & TWAI_MSG_FLAG_RTR;
//Set frame information
tx_frame->dlc = dlc;
tx_frame->frame_format = is_extd;
tx_frame->rtr = is_rtr;
tx_frame->self_reception = (flags & TWAI_MSG_FLAG_SELF) ? 1 : 0;
tx_frame->single_shot = (flags & TWAI_MSG_FLAG_SS) ? 1 : 0;
//Set ID. The ID registers are big endian and left aligned, therefore a bswap will be required
if (is_extd) {
uint32_t id_temp = __builtin_bswap32((id & TWAI_EXTD_ID_MASK) << 3); //((id << 3) >> 8*(3-i))
for (int i = 0; i < 4; i++) {
tx_frame->extended.id[i] = (id_temp >> (8 * i)) & 0xFF;
}
} else {
uint32_t id_temp = __builtin_bswap16((id & TWAI_STD_ID_MASK) << 5); //((id << 5) >> 8*(1-i))
for (int i = 0; i < 2; i++) {
tx_frame->standard.id[i] = (id_temp >> (8 * i)) & 0xFF;
}
}
uint8_t *data_buffer = (is_extd) ? tx_frame->extended.data : tx_frame->standard.data;
if (!is_rtr) { //Only copy data if the frame is a data frame (i.e not a remote frame)
for (int i = 0; (i < dlc) && (i < TWAI_FRAME_MAX_DLC); i++) {
data_buffer[i] = data[i];
}
}
}
/**
* @brief Parse formatted TWAI frame (RX Buffer Layout) into its constituent contents
*
* @param[in] rx_frame Pointer to formatted frame
* @param[out] id 11 or 29bit ID
* @param[out] dlc Data length code
* @param[out] data Data. Left over bytes set to 0.
* @param[out] format Type of TWAI frame
*/
static inline void twai_ll_prase_frame_buffer(twai_ll_frame_buffer_t *rx_frame, uint32_t *id, uint8_t *dlc,
uint8_t *data, uint32_t *flags)
{
//Copy frame information
*dlc = rx_frame->dlc;
uint32_t flags_temp = 0;
flags_temp |= (rx_frame->frame_format) ? TWAI_MSG_FLAG_EXTD : 0;
flags_temp |= (rx_frame->rtr) ? TWAI_MSG_FLAG_RTR : 0;
flags_temp |= (rx_frame->dlc > TWAI_FRAME_MAX_DLC) ? TWAI_MSG_FLAG_DLC_NON_COMP : 0;
*flags = flags_temp;
//Copy ID. The ID registers are big endian and left aligned, therefore a bswap will be required
if (rx_frame->frame_format) {
uint32_t id_temp = 0;
for (int i = 0; i < 4; i++) {
id_temp |= rx_frame->extended.id[i] << (8 * i);
}
id_temp = __builtin_bswap32(id_temp) >> 3; //((byte[i] << 8*(3-i)) >> 3)
*id = id_temp & TWAI_EXTD_ID_MASK;
} else {
uint32_t id_temp = 0;
for (int i = 0; i < 2; i++) {
id_temp |= rx_frame->standard.id[i] << (8 * i);
}
id_temp = __builtin_bswap16(id_temp) >> 5; //((byte[i] << 8*(1-i)) >> 5)
*id = id_temp & TWAI_STD_ID_MASK;
}
uint8_t *data_buffer = (rx_frame->frame_format) ? rx_frame->extended.data : rx_frame->standard.data;
//Only copy data if the frame is a data frame (i.e. not a remote frame)
int data_length = (rx_frame->rtr) ? 0 : ((rx_frame->dlc > TWAI_FRAME_MAX_DLC) ? TWAI_FRAME_MAX_DLC : rx_frame->dlc);
for (int i = 0; i < data_length; i++) {
data[i] = data_buffer[i];
}
//Set remaining bytes of data to 0
for (int i = data_length; i < TWAI_FRAME_MAX_DLC; i++) {
data[i] = 0;
}
}
/* ----------------------- RX Message Count Register ------------------------ */
/**
* @brief Get RX Message Counter
*
* @param hw Start address of the TWAI registers
* @return RX Message Counter
*/
static inline uint32_t twai_ll_get_rx_msg_count(twai_dev_t *hw)
{
return hw->rx_message_counter_reg.val;
}
/* ------------------------- Clock Divider Register ------------------------- */
/**
* @brief Set CLKOUT Divider and enable/disable
*
* Configure CLKOUT. CLKOUT is a pre-scaled version of APB CLK. Divider can be
* 1, or any even number from 2 to 490. Set the divider to 0 to disable CLKOUT.
*
* @param hw Start address of the TWAI registers
* @param divider Divider for CLKOUT (any even number from 2 to 490). Set to 0 to disable CLKOUT
*/
static inline void twai_ll_set_clkout(twai_dev_t *hw, uint32_t divider)
{
if (divider >= 2 && divider <= 490) {
hw->clock_divider_reg.co = 0;
hw->clock_divider_reg.cd = (divider / 2) - 1;
} else if (divider == 1) {
//Setting the divider reg to max value (255) means a divider of 1
hw->clock_divider_reg.co = 0;
hw->clock_divider_reg.cd = 255;
} else {
hw->clock_divider_reg.co = 1;
hw->clock_divider_reg.cd = 0;
}
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,937 @@
// 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.
// The LL layer for UART register operations.
// Note that most of the register operations in this layer are non-atomic operations.
#pragma once
#include "hal/uart_types.h"
#include "soc/uart_periph.h"
#ifdef __cplusplus
extern "C" {
#endif
// The default fifo depth
#define UART_LL_FIFO_DEF_LEN (SOC_UART_FIFO_LEN)
// Get UART hardware instance with giving uart num
#define UART_LL_GET_HW(num) (((num) == 0) ? (&UART0) : (&UART1))
#define UART_LL_MIN_WAKEUP_THRESH (2)
#define UART_LL_INTR_MASK (0x7ffff) //All interrupt mask
#define UART_LL_FSM_IDLE (0x0)
#define UART_LL_FSM_TX_WAIT_SEND (0xf)
// Define UART interrupts
typedef enum {
UART_INTR_RXFIFO_FULL = (0x1 << 0),
UART_INTR_TXFIFO_EMPTY = (0x1 << 1),
UART_INTR_PARITY_ERR = (0x1 << 2),
UART_INTR_FRAM_ERR = (0x1 << 3),
UART_INTR_RXFIFO_OVF = (0x1 << 4),
UART_INTR_DSR_CHG = (0x1 << 5),
UART_INTR_CTS_CHG = (0x1 << 6),
UART_INTR_BRK_DET = (0x1 << 7),
UART_INTR_RXFIFO_TOUT = (0x1 << 8),
UART_INTR_SW_XON = (0x1 << 9),
UART_INTR_SW_XOFF = (0x1 << 10),
UART_INTR_GLITCH_DET = (0x1 << 11),
UART_INTR_TX_BRK_DONE = (0x1 << 12),
UART_INTR_TX_BRK_IDLE = (0x1 << 13),
UART_INTR_TX_DONE = (0x1 << 14),
UART_INTR_RS485_PARITY_ERR = (0x1 << 15),
UART_INTR_RS485_FRM_ERR = (0x1 << 16),
UART_INTR_RS485_CLASH = (0x1 << 17),
UART_INTR_CMD_CHAR_DET = (0x1 << 18),
} uart_intr_t;
static inline void uart_ll_reset_core(uart_dev_t *hw) {
hw->clk_conf.rst_core = 1;
hw->clk_conf.rst_core = 0;
}
static inline void uart_ll_sclk_enable(uart_dev_t *hw) {
hw->clk_conf.sclk_en = 1;
hw->clk_conf.rx_sclk_en = 1;
hw->clk_conf.tx_sclk_en = 1;
}
static inline void uart_ll_sclk_disable(uart_dev_t *hw) {
hw->clk_conf.sclk_en = 0;
hw->clk_conf.rx_sclk_en = 0;
hw->clk_conf.tx_sclk_en = 0;
}
/**
* @brief Set the UART source clock.
*
* @param hw Beginning address of the peripheral registers.
* @param source_clk The UART source clock. The source clock can be APB clock, RTC clock or XTAL clock.
* If the source clock is RTC/XTAL, the UART can still work when the APB changes.
*
* @return None.
*/
static inline void uart_ll_set_sclk(uart_dev_t *hw, uart_sclk_t source_clk)
{
switch (source_clk) {
default:
case UART_SCLK_APB:
hw->clk_conf.sclk_sel = 1;
break;
case UART_SCLK_RTC:
hw->clk_conf.sclk_sel = 2;
break;
case UART_SCLK_XTAL:
hw->clk_conf.sclk_sel = 3;
break;
}
}
/**
* @brief Get the UART source clock type.
*
* @param hw Beginning address of the peripheral registers.
* @param source_clk The pointer to accept the UART source clock type.
*
* @return None.
*/
static inline void uart_ll_get_sclk(uart_dev_t *hw, uart_sclk_t *source_clk)
{
switch (hw->clk_conf.sclk_sel) {
default:
case 1:
*source_clk = UART_SCLK_APB;
break;
case 2:
*source_clk = UART_SCLK_RTC;
break;
case 3:
*source_clk = UART_SCLK_XTAL;
break;
}
}
/**
* @brief Get the UART source clock frequency.
*
* @param hw Beginning address of the peripheral registers.
*
* @return Current source clock frequency
*/
static inline uint32_t uart_ll_get_sclk_freq(uart_dev_t *hw)
{
switch (hw->clk_conf.sclk_sel) {
default:
case 1:
return APB_CLK_FREQ;
case 2:
return RTC_CLK_FREQ;
case 3:
return XTAL_CLK_FREQ;
}
}
/**
* @brief Configure the baud-rate.
*
* @param hw Beginning address of the peripheral registers.
* @param baud The baud rate to be set.
*
* @return None
*/
static inline void uart_ll_set_baudrate(uart_dev_t *hw, uint32_t baud)
{
#define DIV_UP(a, b) (((a) + (b) - 1) / (b))
uint32_t sclk_freq = uart_ll_get_sclk_freq(hw);
const uint32_t max_div = BIT(12) - 1; // UART divider integer part only has 12 bits
int sclk_div = DIV_UP(sclk_freq, max_div * baud);
uint32_t clk_div = ((sclk_freq) << 4) / (baud * sclk_div);
// The baud rate configuration register is divided into
// an integer part and a fractional part.
hw->clk_div.div_int = clk_div >> 4;
hw->clk_div.div_frag = clk_div & 0xf;
hw->clk_conf.sclk_div_num = sclk_div - 1;
#undef DIV_UP
}
/**
* @brief Get the current baud-rate.
*
* @param hw Beginning address of the peripheral registers.
*
* @return The current baudrate
*/
static inline uint32_t uart_ll_get_baudrate(uart_dev_t *hw)
{
uint32_t sclk_freq = uart_ll_get_sclk_freq(hw);
typeof(hw->clk_div) div_reg = hw->clk_div;
return ((sclk_freq << 4)) / (((div_reg.div_int << 4) | div_reg.div_frag) * (hw->clk_conf.sclk_div_num + 1));
}
/**
* @brief Enable the UART interrupt based on the given mask.
*
* @param hw Beginning address of the peripheral registers.
* @param mask The bitmap of the interrupts need to be enabled.
*
* @return None
*/
static inline void uart_ll_ena_intr_mask(uart_dev_t *hw, uint32_t mask)
{
hw->int_ena.val |= mask;
}
/**
* @brief Disable the UART interrupt based on the given mask.
*
* @param hw Beginning address of the peripheral registers.
* @param mask The bitmap of the interrupts need to be disabled.
*
* @return None
*/
static inline void uart_ll_disable_intr_mask(uart_dev_t *hw, uint32_t mask)
{
hw->int_ena.val &= (~mask);
}
/**
* @brief Get the UART interrupt status.
*
* @param hw Beginning address of the peripheral registers.
*
* @return The UART interrupt status.
*/
static inline uint32_t uart_ll_get_intsts_mask(uart_dev_t *hw)
{
return hw->int_st.val;
}
/**
* @brief Clear the UART interrupt status based on the given mask.
*
* @param hw Beginning address of the peripheral registers.
* @param mask The bitmap of the interrupts need to be cleared.
*
* @return None
*/
static inline void uart_ll_clr_intsts_mask(uart_dev_t *hw, uint32_t mask)
{
hw->int_clr.val = mask;
}
/**
* @brief Get status of enabled interrupt.
*
* @param hw Beginning address of the peripheral registers.
*
* @return interrupt enable value
*/
static inline uint32_t uart_ll_get_intr_ena_status(uart_dev_t *hw)
{
return hw->int_ena.val;
}
/**
* @brief Read the UART rxfifo.
*
* @param hw Beginning address of the peripheral registers.
* @param buf The data buffer. The buffer size should be large than 128 byts.
* @param rd_len The data length needs to be read.
*
* @return None.
*/
static inline void uart_ll_read_rxfifo(uart_dev_t *hw, uint8_t *buf, uint32_t rd_len)
{
for (int i = 0; i < (int)rd_len; i++) {
buf[i] = hw->ahb_fifo.rw_byte;
}
}
/**
* @brief Write byte to the UART txfifo.
*
* @param hw Beginning address of the peripheral registers.
* @param buf The data buffer.
* @param wr_len The data length needs to be writen.
*
* @return None
*/
static inline void uart_ll_write_txfifo(uart_dev_t *hw, const uint8_t *buf, uint32_t wr_len)
{
for (int i = 0; i < (int)wr_len; i++) {
hw->ahb_fifo.rw_byte = buf[i];
}
}
/**
* @brief Reset the UART hw rxfifo.
*
* @param hw Beginning address of the peripheral registers.
*
* @return None
*/
static inline void uart_ll_rxfifo_rst(uart_dev_t *hw)
{
hw->conf0.rxfifo_rst = 1;
hw->conf0.rxfifo_rst = 0;
}
/**
* @brief Reset the UART hw txfifo.
*
* @param hw Beginning address of the peripheral registers.
*
* @return None
*/
static inline void uart_ll_txfifo_rst(uart_dev_t *hw)
{
hw->conf0.txfifo_rst = 1;
hw->conf0.txfifo_rst = 0;
}
/**
* @brief Get the length of readable data in UART rxfifo.
*
* @param hw Beginning address of the peripheral registers.
*
* @return The readable data length in rxfifo.
*/
static inline uint32_t uart_ll_get_rxfifo_len(uart_dev_t *hw)
{
return hw->status.rxfifo_cnt;
}
/**
* @brief Get the writable data length of UART txfifo.
*
* @param hw Beginning address of the peripheral registers.
*
* @return The data length of txfifo can be written.
*/
static inline uint32_t uart_ll_get_txfifo_len(uart_dev_t *hw)
{
return UART_LL_FIFO_DEF_LEN - hw->status.txfifo_cnt;
}
/**
* @brief Configure the UART stop bit.
*
* @param hw Beginning address of the peripheral registers.
* @param stop_bit The stop bit number to be set.
*
* @return None.
*/
static inline void uart_ll_set_stop_bits(uart_dev_t *hw, uart_stop_bits_t stop_bit)
{
hw->conf0.stop_bit_num = stop_bit;
}
/**
* @brief Get the configuration of the UART stop bit.
*
* @param hw Beginning address of the peripheral registers.
* @param stop_bit The pointer to accept the stop bit configuration
*
* @return None.
*/
static inline void uart_ll_get_stop_bits(uart_dev_t *hw, uart_stop_bits_t *stop_bit)
{
*stop_bit = hw->conf0.stop_bit_num;
}
/**
* @brief Configure the UART parity check mode.
*
* @param hw Beginning address of the peripheral registers.
* @param parity_mode The parity check mode to be set.
*
* @return None.
*/
static inline void uart_ll_set_parity(uart_dev_t *hw, uart_parity_t parity_mode)
{
if (parity_mode != UART_PARITY_DISABLE) {
hw->conf0.parity = parity_mode & 0x1;
}
hw->conf0.parity_en = (parity_mode >> 1) & 0x1;
}
/**
* @brief Get the UART parity check mode configuration.
*
* @param hw Beginning address of the peripheral registers.
* @param parity_mode The pointer to accept the parity check mode configuration.
*
* @return None.
*/
static inline void uart_ll_get_parity(uart_dev_t *hw, uart_parity_t *parity_mode)
{
if (hw->conf0.parity_en) {
*parity_mode = 0X2 | hw->conf0.parity;
} else {
*parity_mode = UART_PARITY_DISABLE;
}
}
/**
* @brief Set the UART rxfifo full threshold value. When the data in rxfifo is more than the threshold value,
* it will produce rxfifo_full_int_raw interrupt.
*
* @param hw Beginning address of the peripheral registers.
* @param full_thrhd The full threshold value of the rxfifo. `full_thrhd` should be less than `UART_LL_FIFO_DEF_LEN`.
*
* @return None.
*/
static inline void uart_ll_set_rxfifo_full_thr(uart_dev_t *hw, uint16_t full_thrhd)
{
hw->conf1.rxfifo_full_thrhd = full_thrhd;
}
/**
* @brief Set the txfifo empty threshold. when the data length in txfifo is less than threshold value,
* it will produce txfifo_empty_int_raw interrupt.
*
* @param hw Beginning address of the peripheral registers.
* @param empty_thrhd The empty threshold of txfifo.
*
* @return None.
*/
static inline void uart_ll_set_txfifo_empty_thr(uart_dev_t *hw, uint16_t empty_thrhd)
{
hw->conf1.txfifo_empty_thrhd = empty_thrhd;
}
/**
* @brief Set the UART rx-idle threshold value. when receiver takes more time than rx_idle_thrhd to receive a byte data,
* it will produce frame end signal for uhci to stop receiving data.
*
* @param hw Beginning address of the peripheral registers.
* @param rx_idle_thr The rx-idle threshold to be set.
*
* @return None.
*/
static inline void uart_ll_set_rx_idle_thr(uart_dev_t *hw, uint32_t rx_idle_thr)
{
hw->idle_conf.rx_idle_thrhd = rx_idle_thr;
}
/**
* @brief Configure the duration time between transfers.
*
* @param hw Beginning address of the peripheral registers.
* @param idle_num the duration time between transfers.
*
* @return None.
*/
static inline void uart_ll_set_tx_idle_num(uart_dev_t *hw, uint32_t idle_num)
{
hw->idle_conf.tx_idle_num = idle_num;
}
/**
* @brief Configure the transmiter to send break chars.
*
* @param hw Beginning address of the peripheral registers.
* @param break_num The number of the break chars need to be send.
*
* @return None.
*/
static inline void uart_ll_tx_break(uart_dev_t *hw, uint32_t break_num)
{
if (break_num > 0) {
hw->txbrk_conf.tx_brk_num = break_num;
hw->conf0.txd_brk = 1;
} else {
hw->conf0.txd_brk = 0;
}
}
/**
* @brief Configure the UART hardware flow control.
*
* @param hw Beginning address of the peripheral registers.
* @param flow_ctrl The hw flow control configuration.
* @param rx_thrs The rx flow control signal will be active if the data length in rxfifo is more than this value.
*
* @return None.
*/
static inline void uart_ll_set_hw_flow_ctrl(uart_dev_t *hw, uart_hw_flowcontrol_t flow_ctrl, uint32_t rx_thrs)
{
//only when UART_HW_FLOWCTRL_RTS is set , will the rx_thresh value be set.
if (flow_ctrl & UART_HW_FLOWCTRL_RTS) {
hw->mem_conf.rx_flow_thrhd = rx_thrs;
hw->conf1.rx_flow_en = 1;
} else {
hw->conf1.rx_flow_en = 0;
}
if (flow_ctrl & UART_HW_FLOWCTRL_CTS) {
hw->conf0.tx_flow_en = 1;
} else {
hw->conf0.tx_flow_en = 0;
}
}
/**
* @brief Configure the hardware flow control.
*
* @param hw Beginning address of the peripheral registers.
* @param flow_ctrl A pointer to accept the hw flow control configuration.
*
* @return None.
*/
static inline void uart_ll_get_hw_flow_ctrl(uart_dev_t *hw, uart_hw_flowcontrol_t *flow_ctrl)
{
*flow_ctrl = UART_HW_FLOWCTRL_DISABLE;
if (hw->conf1.rx_flow_en) {
*flow_ctrl |= UART_HW_FLOWCTRL_RTS;
}
if (hw->conf0.tx_flow_en) {
*flow_ctrl |= UART_HW_FLOWCTRL_CTS;
}
}
/**
* @brief Configure the software flow control.
*
* @param hw Beginning address of the peripheral registers.
* @param flow_ctrl The UART sofware flow control settings.
* @param sw_flow_ctrl_en Set true to enable software flow control, otherwise set it false.
*
* @return None.
*/
static inline void uart_ll_set_sw_flow_ctrl(uart_dev_t *hw, uart_sw_flowctrl_t *flow_ctrl, bool sw_flow_ctrl_en)
{
if (sw_flow_ctrl_en) {
hw->flow_conf.xonoff_del = 1;
hw->flow_conf.sw_flow_con_en = 1;
hw->swfc_conf1.xon_threshold = flow_ctrl->xon_thrd;
hw->swfc_conf0.xoff_threshold = flow_ctrl->xoff_thrd;
hw->swfc_conf1.xon_char = flow_ctrl->xon_char;
hw->swfc_conf0.xoff_char = flow_ctrl->xoff_char;
} else {
hw->flow_conf.sw_flow_con_en = 0;
hw->flow_conf.xonoff_del = 0;
}
}
/**
* @brief Configure the AT cmd char. When the receiver receives a continuous AT cmd char, it will produce at_cmd_char_det interrupt.
*
* @param hw Beginning address of the peripheral registers.
* @param cmd_char The AT cmd char configuration.The configuration member is:
* - cmd_char The AT cmd character
* - char_num The number of received AT cmd char must be equal to or greater than this value
* - gap_tout The interval between each AT cmd char, when the duration is less than this value, it will not take this data as AT cmd char
* - pre_idle The idle time before the first AT cmd char, when the duration is less than this value, it will not take the previous data as the last AT cmd char
* - post_idle The idle time after the last AT cmd char, when the duration is less than this value, it will not take this data as the first AT cmd char
*
* @return None.
*/
static inline void uart_ll_set_at_cmd_char(uart_dev_t *hw, uart_at_cmd_t *cmd_char)
{
hw->at_cmd_char.data = cmd_char->cmd_char;
hw->at_cmd_char.char_num = cmd_char->char_num;
hw->at_cmd_postcnt.post_idle_num = cmd_char->post_idle;
hw->at_cmd_precnt.pre_idle_num = cmd_char->pre_idle;
hw->at_cmd_gaptout.rx_gap_tout = cmd_char->gap_tout;
}
/**
* @brief Set the UART data bit mode.
*
* @param hw Beginning address of the peripheral registers.
* @param data_bit The data bit mode to be set.
*
* @return None.
*/
static inline void uart_ll_set_data_bit_num(uart_dev_t *hw, uart_word_length_t data_bit)
{
hw->conf0.bit_num = data_bit;
}
/**
* @brief Set the rts active level.
*
* @param hw Beginning address of the peripheral registers.
* @param level The rts active level, 0 or 1.
*
* @return None.
*/
static inline void uart_ll_set_rts_active_level(uart_dev_t *hw, int level)
{
hw->conf0.sw_rts = level & 0x1;
}
/**
* @brief Set the dtr active level.
*
* @param hw Beginning address of the peripheral registers.
* @param level The dtr active level, 0 or 1.
*
* @return None.
*/
static inline void uart_ll_set_dtr_active_level(uart_dev_t *hw, int level)
{
hw->conf0.sw_dtr = level & 0x1;
}
/**
* @brief Set the UART wakeup threshold.
*
* @param hw Beginning address of the peripheral registers.
* @param wakeup_thrd The wakeup threshold value to be set. When the input rx edge changes more than this value,
* the UART will active from light sleeping mode.
*
* @return None.
*/
static inline void uart_ll_set_wakeup_thrd(uart_dev_t *hw, uint32_t wakeup_thrd)
{
hw->sleep_conf.active_threshold = wakeup_thrd - UART_LL_MIN_WAKEUP_THRESH;
}
/**
* @brief Configure the UART work in normal mode.
*
* @param hw Beginning address of the peripheral registers.
*
* @return None.
*/
static inline void uart_ll_set_mode_normal(uart_dev_t *hw)
{
hw->rs485_conf.en = 0;
hw->rs485_conf.tx_rx_en = 0;
hw->rs485_conf.rx_busy_tx_en = 0;
hw->conf0.irda_en = 0;
}
/**
* @brief Configure the UART work in rs485_app_ctrl mode.
*
* @param hw Beginning address of the peripheral registers.
*
* @return None.
*/
static inline void uart_ll_set_mode_rs485_app_ctrl(uart_dev_t *hw)
{
// Application software control, remove echo
hw->rs485_conf.rx_busy_tx_en = 1;
hw->conf0.irda_en = 0;
hw->conf0.sw_rts = 0;
hw->conf0.irda_en = 0;
hw->rs485_conf.dl0_en = 1;
hw->rs485_conf.dl1_en = 1;
hw->rs485_conf.en = 1;
}
/**
* @brief Configure the UART work in rs485_half_duplex mode.
*
* @param hw Beginning address of the peripheral registers.
*
* @return None.
*/
static inline void uart_ll_set_mode_rs485_half_duplex(uart_dev_t *hw)
{
// Enable receiver, sw_rts = 1 generates low level on RTS pin
hw->conf0.sw_rts = 1;
// Half duplex mode
hw->rs485_conf.tx_rx_en = 0;
// Setting this bit will allow data to be transmitted while receiving data(full-duplex mode).
// But note that this full-duplex mode has no conflict detection function
hw->rs485_conf.rx_busy_tx_en = 0;
hw->conf0.irda_en = 0;
hw->rs485_conf.dl0_en = 1;
hw->rs485_conf.dl1_en = 1;
hw->rs485_conf.en = 1;
}
/**
* @brief Configure the UART work in collision_detect mode.
*
* @param hw Beginning address of the peripheral registers.
*
* @return None.
*/
static inline void uart_ll_set_mode_collision_detect(uart_dev_t *hw)
{
hw->conf0.irda_en = 0;
// Enable full-duplex mode
hw->rs485_conf.tx_rx_en = 1;
// Transmitter should send data when the receiver is busy,
hw->rs485_conf.rx_busy_tx_en = 1;
hw->rs485_conf.dl0_en = 1;
hw->rs485_conf.dl1_en = 1;
hw->conf0.sw_rts = 0;
hw->rs485_conf.en = 1;
}
/**
* @brief Configure the UART work in irda mode.
*
* @param hw Beginning address of the peripheral registers.
*
* @return None.
*/
static inline void uart_ll_set_mode_irda(uart_dev_t *hw)
{
hw->rs485_conf.en = 0;
hw->rs485_conf.tx_rx_en = 0;
hw->rs485_conf.rx_busy_tx_en = 0;
hw->conf0.sw_rts = 0;
hw->conf0.irda_en = 1;
}
/**
* @brief Set uart mode.
*
* @param hw Beginning address of the peripheral registers.
* @param mode The UART mode to be set.
*
* @return None.
*/
static inline void uart_ll_set_mode(uart_dev_t *hw, uart_mode_t mode)
{
switch (mode) {
default:
case UART_MODE_UART:
uart_ll_set_mode_normal(hw);
break;
case UART_MODE_RS485_COLLISION_DETECT:
uart_ll_set_mode_collision_detect(hw);
break;
case UART_MODE_RS485_APP_CTRL:
uart_ll_set_mode_rs485_app_ctrl(hw);
break;
case UART_MODE_RS485_HALF_DUPLEX:
uart_ll_set_mode_rs485_half_duplex(hw);
break;
case UART_MODE_IRDA:
uart_ll_set_mode_irda(hw);
break;
}
}
/**
* @brief Get the UART AT cmd char configuration.
*
* @param hw Beginning address of the peripheral registers.
* @param cmd_char The Pointer to accept value of UART AT cmd char.
* @param char_num Pointer to accept the repeat number of UART AT cmd char.
*
* @return None.
*/
static inline void uart_ll_get_at_cmd_char(uart_dev_t *hw, uint8_t *cmd_char, uint8_t *char_num)
{
*cmd_char = hw->at_cmd_char.data;
*char_num = hw->at_cmd_char.char_num;
}
/**
* @brief Get the UART wakeup threshold value.
*
* @param hw Beginning address of the peripheral registers.
*
* @return The UART wakeup threshold value.
*/
static inline uint32_t uart_ll_get_wakeup_thrd(uart_dev_t *hw)
{
return hw->sleep_conf.active_threshold + UART_LL_MIN_WAKEUP_THRESH;
}
/**
* @brief Get the UART data bit configuration.
*
* @param hw Beginning address of the peripheral registers.
* @param data_bit The pointer to accept the UART data bit configuration.
*
* @return The bit mode.
*/
static inline void uart_ll_get_data_bit_num(uart_dev_t *hw, uart_word_length_t *data_bit)
{
*data_bit = hw->conf0.bit_num;
}
/**
* @brief Check if the UART sending state machine is in the IDLE state.
*
* @param hw Beginning address of the peripheral registers.
*
* @return True if the state machine is in the IDLE state, otherwise false is returned.
*/
static inline bool uart_ll_is_tx_idle(uart_dev_t *hw)
{
return ((hw->status.txfifo_cnt == 0) && (hw->fsm_status.st_utx_out == 0));
}
/**
* @brief Check if the UART rts flow control is enabled.
*
* @param hw Beginning address of the peripheral registers.
*
* @return True if hw rts flow control is enabled, otherwise false is returned.
*/
static inline bool uart_ll_is_hw_rts_en(uart_dev_t *hw)
{
return hw->conf1.rx_flow_en;
}
/**
* @brief Check if the UART cts flow control is enabled.
*
* @param hw Beginning address of the peripheral registers.
*
* @return True if hw cts flow control is enabled, otherwise false is returned.
*/
static inline bool uart_ll_is_hw_cts_en(uart_dev_t *hw)
{
return hw->conf0.tx_flow_en;
}
/**
* @brief Configure TX signal loop back to RX module, just for the testing purposes
*
* @param hw Beginning address of the peripheral registers.
* @param loop_back_en Set ture to enable the loop back function, else set it false.
*
* @return None
*/
static inline void uart_ll_set_loop_back(uart_dev_t *hw, bool loop_back_en)
{
hw->conf0.loopback = loop_back_en;
}
static inline void uart_ll_xon_force_on(uart_dev_t *hw, bool always_on)
{
hw->flow_conf.force_xon = 1;
if(!always_on) {
hw->flow_conf.force_xon = 0;
}
}
/**
* @brief Inverse the UART signal with the given mask.
*
* @param hw Beginning address of the peripheral registers.
* @param inv_mask The UART signal bitmap needs to be inversed.
* Use the ORred mask of `uart_signal_inv_t`;
*
* @return None.
*/
static inline void uart_ll_inverse_signal(uart_dev_t *hw, uint32_t inv_mask)
{
typeof(hw->conf0) conf0_reg = hw->conf0;
conf0_reg.irda_tx_inv = (inv_mask & UART_SIGNAL_IRDA_TX_INV) ? 1 : 0;
conf0_reg.irda_rx_inv = (inv_mask & UART_SIGNAL_IRDA_RX_INV) ? 1 : 0;
conf0_reg.rxd_inv = (inv_mask & UART_SIGNAL_RXD_INV) ? 1 : 0;
conf0_reg.cts_inv = (inv_mask & UART_SIGNAL_CTS_INV) ? 1 : 0;
conf0_reg.dsr_inv = (inv_mask & UART_SIGNAL_DSR_INV) ? 1 : 0;
conf0_reg.txd_inv = (inv_mask & UART_SIGNAL_TXD_INV) ? 1 : 0;
conf0_reg.rts_inv = (inv_mask & UART_SIGNAL_RTS_INV) ? 1 : 0;
conf0_reg.dtr_inv = (inv_mask & UART_SIGNAL_DTR_INV) ? 1 : 0;
hw->conf0.val = conf0_reg.val;
}
/**
* @brief Configure the timeout value for receiver receiving a byte, and enable rx timeout function.
*
* @param hw Beginning address of the peripheral registers.
* @param tout_thrd The timeout value as UART bit time. The rx timeout function will be disabled if `tout_thrd == 0`.
*
* @return None.
*/
static inline void uart_ll_set_rx_tout(uart_dev_t *hw, uint16_t tout_thrd)
{
uint16_t tout_val = tout_thrd;
if(tout_thrd > 0) {
hw->mem_conf.rx_tout_thrhd = tout_val;
hw->conf1.rx_tout_en = 1;
} else {
hw->conf1.rx_tout_en = 0;
}
}
/**
* @brief Get the timeout value for receiver receiving a byte.
*
* @param hw Beginning address of the peripheral registers.
*
* @return tout_thr The timeout threshold value. If timeout feature is disabled returns 0.
*/
static inline uint16_t uart_ll_get_rx_tout_thr(uart_dev_t *hw)
{
uint16_t tout_thrd = 0;
if(hw->conf1.rx_tout_en > 0) {
tout_thrd = hw->mem_conf.rx_tout_thrhd;
}
return tout_thrd;
}
/**
* @brief Get UART maximum timeout threshold.
*
* @param hw Beginning address of the peripheral registers.
*
* @return maximum timeout threshold.
*/
static inline uint16_t uart_ll_max_tout_thrd(uart_dev_t *hw)
{
return UART_RX_TOUT_THRHD_V;
}
/**
* @brief Force UART xoff.
*
* @param uart_num UART port number, the max port number is (UART_NUM_MAX -1).
*
* @return None.
*/
static inline void uart_ll_force_xoff(uart_port_t uart_num)
{
REG_CLR_BIT(UART_FLOW_CONF_REG(uart_num), UART_FORCE_XON);
REG_SET_BIT(UART_FLOW_CONF_REG(uart_num), UART_SW_FLOW_CON_EN | UART_FORCE_XOFF);
REG_SET_BIT(UART_ID_REG(uart_num), UART_UPDATE);
}
/**
* @brief Force UART xon.
*
* @param uart_num UART port number, the max port number is (UART_NUM_MAX -1).
*
* @return None.
*/
static inline void uart_ll_force_xon(uart_port_t uart_num)
{
REG_CLR_BIT(UART_FLOW_CONF_REG(uart_num), UART_FORCE_XOFF);
REG_SET_BIT(UART_FLOW_CONF_REG(uart_num), UART_FORCE_XON);
REG_CLR_BIT(UART_FLOW_CONF_REG(uart_num), UART_SW_FLOW_CON_EN | UART_FORCE_XON);
REG_SET_BIT(UART_ID_REG(uart_num), UART_UPDATE);
}
/**
* @brief Get UART final state machine status.
*
* @param uart_num UART port number, the max port number is (UART_NUM_MAX -1).
*
* @return UART module FSM status.
*/
static inline uint32_t uart_ll_get_fsm_status(uart_port_t uart_num)
{
return REG_GET_FIELD(UART_FSM_STATUS_REG(uart_num), UART_ST_UTX_OUT);
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,130 @@
// 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.
// The LL layer for UHCI register operations.
// Note that most of the register operations in this layer are non-atomic operations.
#pragma once
#include <stdio.h>
#include "uhci_types.h"
#include "soc/uhci_struct.h"
#define UHCI_LL_GET_HW(num) (((num) == 0) ? (&UHCI0) : (NULL))
typedef enum {
UHCI_RX_BREAK_CHR_EOF = 0x1,
UHCI_RX_IDLE_EOF = 0x2,
UHCI_RX_LEN_EOF = 0x4,
UHCI_RX_EOF_MAX = 0x7,
} uhci_rxeof_cfg_t;
static inline void uhci_ll_init(uhci_dev_t *hw)
{
typeof(hw->conf0) conf0_reg;
hw->conf0.clk_en = 1;
conf0_reg.val = 0;
conf0_reg.clk_en = 1;
hw->conf0.val = conf0_reg.val;
hw->conf1.val = 0;
}
static inline void uhci_ll_attach_uart_port(uhci_dev_t *hw, int uart_num)
{
hw->conf0.uart0_ce = (uart_num == 0)? 1: 0;
hw->conf0.uart1_ce = (uart_num == 1)? 1: 0;
}
static inline void uhci_ll_set_seper_chr(uhci_dev_t *hw, uhci_seper_chr_t *seper_char)
{
if (seper_char->sub_chr_en) {
typeof(hw->esc_conf0) esc_conf0_reg = hw->esc_conf0;
esc_conf0_reg.seper_char = seper_char->seper_chr;
esc_conf0_reg.seper_esc_char0 = seper_char->sub_chr1;
esc_conf0_reg.seper_esc_char1 = seper_char->sub_chr2;
hw->esc_conf0.val = esc_conf0_reg.val;
hw->escape_conf.tx_c0_esc_en = 1;
hw->escape_conf.rx_c0_esc_en = 1;
} else {
hw->escape_conf.tx_c0_esc_en = 0;
hw->escape_conf.rx_c0_esc_en = 0;
}
}
static inline void uhci_ll_get_seper_chr(uhci_dev_t *hw, uhci_seper_chr_t *seper_chr)
{
(void)hw;
(void)seper_chr;
}
static inline void uhci_ll_set_swflow_ctrl_sub_chr(uhci_dev_t *hw, uhci_swflow_ctrl_sub_chr_t *sub_ctr)
{
typeof(hw->escape_conf) escape_conf_reg = hw->escape_conf;
if (sub_ctr->flow_en == 1) {
typeof(hw->esc_conf2) esc_conf2_reg = hw->esc_conf2;
typeof(hw->esc_conf3) esc_conf3_reg = hw->esc_conf3;
esc_conf2_reg.seq1 = sub_ctr->xon_chr;
esc_conf2_reg.seq1_char0 = sub_ctr->xon_sub1;
esc_conf2_reg.seq1_char1 = sub_ctr->xon_sub2;
esc_conf3_reg.seq2 = sub_ctr->xoff_chr;
esc_conf3_reg.seq2_char0 = sub_ctr->xoff_sub1;
esc_conf3_reg.seq2_char1 = sub_ctr->xoff_sub2;
escape_conf_reg.tx_11_esc_en = 1;
escape_conf_reg.tx_13_esc_en = 1;
escape_conf_reg.rx_11_esc_en = 1;
escape_conf_reg.rx_13_esc_en = 1;
hw->esc_conf2.val = esc_conf2_reg.val;
hw->esc_conf3.val = esc_conf3_reg.val;
} else {
escape_conf_reg.tx_11_esc_en = 0;
escape_conf_reg.tx_13_esc_en = 0;
escape_conf_reg.rx_11_esc_en = 0;
escape_conf_reg.rx_13_esc_en = 0;
}
hw->escape_conf.val = escape_conf_reg.val;
}
static inline void uhci_ll_enable_intr(uhci_dev_t *hw, uint32_t intr_mask)
{
hw->int_ena.val |= intr_mask;
}
static inline void uhci_ll_disable_intr(uhci_dev_t *hw, uint32_t intr_mask)
{
hw->int_ena.val &= (~intr_mask);
}
static inline void uhci_ll_clear_intr(uhci_dev_t *hw, uint32_t intr_mask)
{
hw->int_clr.val = intr_mask;
}
static inline uint32_t uhci_ll_get_intr(uhci_dev_t *hw)
{
return hw->int_st.val;
}
static inline void uhci_ll_set_eof_mode(uhci_dev_t *hw, uint32_t eof_mode)
{
if (eof_mode & UHCI_RX_BREAK_CHR_EOF) {
hw->conf0.uart_rx_brk_eof_en = 1;
}
if (eof_mode & UHCI_RX_IDLE_EOF) {
hw->conf0.uart_idle_eof_en = 1;
}
if (eof_mode & UHCI_RX_LEN_EOF) {
hw->conf0.len_eof_en = 1;
}
}

View File

@ -0,0 +1,54 @@
// Copyright 2015-2019 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.
// Though the UHCI driver hasn't been published, some types are defined here
// for users to develop over the HAL. See example: controller_hci_uart_esp32c3
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <stdbool.h>
/**
* @brief UHCI escape sequence
*/
typedef struct {
uint8_t seper_chr; /*!< escape sequence character */
uint8_t sub_chr1; /*!< escape sequence sub-character 1 */
uint8_t sub_chr2; /*!< escape sequence sub-character 2 */
bool sub_chr_en; /*!< enable use of sub-chaacter of escape sequence */
} uhci_seper_chr_t;
/**
* @brief UHCI software flow control
*/
typedef struct {
uint8_t xon_chr; /*!< character for XON */
uint8_t xon_sub1; /*!< sub-character 1 for XON */
uint8_t xon_sub2; /*!< sub-character 2 for XON */
uint8_t xoff_chr; /*!< character 2 for XOFF */
uint8_t xoff_sub1; /*!< sub-character 1 for XOFF */
uint8_t xoff_sub2; /*!< sub-character 2 for XOFF */
uint8_t flow_en; /*!< enable use of software flow control */
} uhci_swflow_ctrl_sub_chr_t;
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,169 @@
// Copyright 2021 Espressif Systems (Shanghai)
//
// 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.
// The LL layer of the USB-serial-jtag controller
#pragma once
#include "soc/usb_serial_jtag_reg.h"
#include "soc/usb_serial_jtag_struct.h"
#ifdef __cplusplus
extern "C" {
#endif
//The in and out endpoints are this long.
#define USB_SERIAL_JTAG_PACKET_SZ_BYTES 64
#define USB_SERIAL_JTAG_LL_INTR_MASK (0x7ffff) //All interrupt mask
// Define USB_SERIAL_JTAG interrupts
// Note the hardware has more interrupts, but they're only useful for debugging
// the hardware.
typedef enum {
USB_SERIAL_JTAG_INTR_SOF = (1 << 1),
USB_SERIAL_JTAG_INTR_SERIAL_OUT_RECV_PKT = (1 << 2),
USB_SERIAL_JTAG_INTR_SERIAL_IN_EMPTY = (1 << 3),
USB_SERIAL_JTAG_INTR_TOKEN_REC_IN_EP1 = (1 << 8),
USB_SERIAL_JTAG_INTR_BUS_RESET = (1 << 9),
USB_SERIAL_JTAG_INTR_EP1_ZERO_PAYLOAD = (1 << 10),
} usb_serial_jtag_intr_t;
/**
* @brief Enable the USB_SERIAL_JTAG interrupt based on the given mask.
*
* @param mask The bitmap of the interrupts need to be enabled.
*
* @return None
*/
static inline void usb_serial_jtag_ll_ena_intr_mask(uint32_t mask)
{
USB_SERIAL_JTAG.int_ena.val |= mask;
}
/**
* @brief Disable the USB_SERIAL_JTAG interrupt based on the given mask.
*
* @param mask The bitmap of the interrupts need to be disabled.
*
* @return None
*/
static inline void usb_serial_jtag_ll_disable_intr_mask(uint32_t mask)
{
USB_SERIAL_JTAG.int_ena.val &= (~mask);
}
/**
* @brief Get the USB_SERIAL_JTAG interrupt status.
*
* @return The USB_SERIAL_JTAG interrupt status.
*/
static inline uint32_t usb_serial_jtag_ll_get_intsts_mask(void)
{
return USB_SERIAL_JTAG.int_st.val;
}
/**
* @brief Clear the USB_SERIAL_JTAG interrupt status based on the given mask.
*
* @param mask The bitmap of the interrupts need to be cleared.
*
* @return None
*/
static inline void usb_serial_jtag_ll_clr_intsts_mask(uint32_t mask)
{
USB_SERIAL_JTAG.int_clr.val = mask;
}
/**
* @brief Get status of enabled interrupt.
*
* @return interrupt enable value
*/
static inline uint32_t usb_serial_jtag_ll_get_intr_ena_status(void)
{
return USB_SERIAL_JTAG.int_ena.val;
}
/**
* @brief Read the bytes from the USB_SERIAL_JTAG rxfifo.
*
* @param buf The data buffer.
* @param rd_len The data length needs to be read.
*
* @return amount of bytes read
*/
static inline int usb_serial_jtag_ll_read_rxfifo(uint8_t *buf, uint32_t rd_len)
{
int i;
for (i = 0; i < (int)rd_len; i++) {
if (!USB_SERIAL_JTAG.ep1_conf.serial_out_ep_data_avail) break;
buf[i] = USB_SERIAL_JTAG.ep1.rdwr_byte;
}
return i;
}
/**
* @brief Write byte to the USB_SERIAL_JTAG txfifo. Only writes bytes as long / if there
* is room in the buffer.
*
* @param buf The data buffer.
* @param wr_len The data length needs to be writen.
*
* @return Amount of bytes actually written. May be less than wr_len.
*/
static inline int usb_serial_jtag_ll_write_txfifo(const uint8_t *buf, uint32_t wr_len)
{
int i;
for (i = 0; i < (int)wr_len; i++) {
if (!USB_SERIAL_JTAG.ep1_conf.serial_in_ep_data_free) break;
USB_SERIAL_JTAG.ep1.rdwr_byte = buf[i];
}
return i;
}
/**
* @brief Returns 1 if the USB_SERIAL_JTAG rxfifo has data available.
*
* @return 0 if no data available, 1 if data available
*/
static inline int usb_serial_jtag_ll_rxfifo_data_available(void)
{
return USB_SERIAL_JTAG.ep1_conf.serial_out_ep_data_avail;
}
/**
* @brief Returns 1 if the USB_SERIAL_JTAG txfifo has room.
*
* @return 0 if no data available, 1 if data available
*/
static inline int usb_serial_jtag_ll_txfifo_writable(void)
{
return USB_SERIAL_JTAG.ep1_conf.serial_in_ep_data_free;
}
/**
* @brief Flushes the TX buffer, that is, make it available for the
* host to pick up.
*
* @return na
*/
static inline void usb_serial_jtag_ll_txfifo_flush(void)
{
USB_SERIAL_JTAG.ep1_conf.wr_done=1;
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,61 @@
// Copyright 2015-2019 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.
// The HAL layer for RTC CNTL (common part)
#include "hal/rtc_hal.h"
#include "soc/soc_caps.h"
#include "esp32c3/rom/lldesc.h"
#include "esp_attr.h"
#define RTC_CNTL_HAL_LINK_BUF_SIZE_MIN (SOC_RTC_CNTL_CPU_PD_DMA_BLOCK_SIZE) /* The minimum size of dma link buffer */
typedef struct rtc_cntl_link_buf_conf {
uint32_t cfg[4]; /* 4 word for dma link buffer configuration */
} rtc_cntl_link_buf_conf_t;
void * rtc_cntl_hal_dma_link_init(void *elem, void *buff, int size, void *next)
{
assert(elem != NULL);
assert(buff != NULL);
assert(size >= RTC_CNTL_HAL_LINK_BUF_SIZE_MIN);
lldesc_t *plink = (lldesc_t *)elem;
plink->eof = next ? 0 : 1;
plink->owner = 1;
plink->size = size >> 4; /* in unit of 16 bytes */
plink->length = size >> 4;
plink->buf = buff;
plink->offset = 0;
plink->sosf = 0;
STAILQ_NEXT(plink, qe) = next;
return (void *)plink;
}
void rtc_cntl_hal_enable_cpu_retention(void *addr)
{
if (addr) {
lldesc_t *plink = (lldesc_t *)addr;
/* dma link buffer configure */
rtc_cntl_link_buf_conf_t *pbuf = (rtc_cntl_link_buf_conf_t *)plink->buf;
pbuf->cfg[0] = 0;
pbuf->cfg[1] = 0;
pbuf->cfg[2] = 0;
pbuf->cfg[3] = (uint32_t)-1;
rtc_cntl_ll_enable_cpu_retention((uint32_t)addr);
}
}

View File

@ -0,0 +1,20 @@
set(srcs
"adc_periph.c"
"gdma_periph.c"
"gpio_periph.c"
"interrupts.c"
"spi_periph.c"
"ledc_periph.c"
"rmt_periph.c"
"soc_memory_layout.c"
"sigmadelta_periph.c"
"soc_memory_layout.c"
"i2s_periph.c"
"i2c_periph.c"
"uart_periph.c"
"timer_periph.c")
add_prefix(srcs "${CMAKE_CURRENT_LIST_DIR}/" "${srcs}")
target_sources(${COMPONENT_LIB} PRIVATE "${srcs}")
target_include_directories(${COMPONENT_LIB} PUBLIC . include)

View File

@ -0,0 +1,27 @@
// 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/adc_periph.h"
/* Store IO number corresponding to the ADC channel number. */
const int adc_channel_io_map[SOC_ADC_PERIPH_NUM][SOC_ADC_MAX_CHANNEL_NUM] = {
/* ADC1 */
{
ADC1_CHANNEL_0_GPIO_NUM, ADC1_CHANNEL_1_GPIO_NUM, ADC1_CHANNEL_2_GPIO_NUM, ADC1_CHANNEL_3_GPIO_NUM, ADC1_CHANNEL_4_GPIO_NUM
},
/* ADC2 */
{
ADC2_CHANNEL_0_GPIO_NUM, -1, -1, -1, -1
}
};

View File

@ -0,0 +1,37 @@
// 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/gdma_periph.h"
const gdma_signal_conn_t gdma_periph_signals = {
.groups = {
[0] = {
.module = PERIPH_GDMA_MODULE,
.pairs = {
[0] = {
.rx_irq_id = ETS_DMA_CH0_INTR_SOURCE,
.tx_irq_id = ETS_DMA_CH0_INTR_SOURCE,
},
[1] = {
.rx_irq_id = ETS_DMA_CH1_INTR_SOURCE,
.tx_irq_id = ETS_DMA_CH1_INTR_SOURCE,
},
[2] = {
.rx_irq_id = ETS_DMA_CH2_INTR_SOURCE,
.tx_irq_id = ETS_DMA_CH2_INTR_SOURCE,
}
}
}
}
};

View File

@ -0,0 +1,65 @@
// 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/gpio_periph.h"
const uint32_t GPIO_PIN_MUX_REG[SOC_GPIO_PIN_COUNT] = {
IO_MUX_GPIO0_REG,
IO_MUX_GPIO1_REG,
IO_MUX_GPIO2_REG,
IO_MUX_GPIO3_REG,
IO_MUX_GPIO4_REG,
IO_MUX_GPIO5_REG,
IO_MUX_GPIO6_REG,
IO_MUX_GPIO7_REG,
IO_MUX_GPIO8_REG,
IO_MUX_GPIO9_REG,
IO_MUX_GPIO10_REG,
IO_MUX_GPIO11_REG,
IO_MUX_GPIO12_REG,
IO_MUX_GPIO13_REG,
IO_MUX_GPIO14_REG,
IO_MUX_GPIO15_REG,
IO_MUX_GPIO16_REG,
IO_MUX_GPIO17_REG,
IO_MUX_GPIO18_REG,
IO_MUX_GPIO19_REG,
IO_MUX_GPIO20_REG,
IO_MUX_GPIO21_REG,
};
const uint32_t GPIO_HOLD_MASK[SOC_GPIO_PIN_COUNT] = {
BIT(0), //GPIO0
BIT(1), //GPIO1
BIT(2), //GPIO2
BIT(3), //GPIO3
BIT(4), //GPIO4
BIT(5), //GPIO5
BIT(5), //GPIO6
BIT(6), //GPIO7
BIT(3), //GPIO8
BIT(4), //GPIO9
BIT(0), //GPIO10
BIT(15), //GPIO11
BIT(10), //GPIO12
BIT(12), //GPIO13
BIT(8), //GPIO14
BIT(7), //GPIO15
BIT(9), //GPIO16
BIT(11), //GPIO17
BIT(1), //GPIO18
BIT(2), //GPIO19
BIT(13), //GPIO20
BIT(14), //GPIO21
};

View File

@ -0,0 +1,183 @@
// 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
/**
* @file i2c_apll.h
* @brief Register definitions for digital PLL (BBPLL)
*
* This file lists register fields of BBPLL, located on an internal configuration
* bus. These definitions are used via macros defined in i2c_rtc_clk.h, by
* rtc_clk_cpu_freq_set function in rtc_clk.c.
*/
#define I2C_BBPLL 0x66
#define I2C_BBPLL_HOSTID 1
#define I2C_BBPLL_IR_CAL_DELAY 0
#define I2C_BBPLL_IR_CAL_DELAY_MSB 3
#define I2C_BBPLL_IR_CAL_DELAY_LSB 0
#define I2C_BBPLL_IR_CAL_CK_DIV 0
#define I2C_BBPLL_IR_CAL_CK_DIV_MSB 7
#define I2C_BBPLL_IR_CAL_CK_DIV_LSB 4
#define I2C_BBPLL_IR_CAL_EXT_CAP 1
#define I2C_BBPLL_IR_CAL_EXT_CAP_MSB 3
#define I2C_BBPLL_IR_CAL_EXT_CAP_LSB 0
#define I2C_BBPLL_IR_CAL_ENX_CAP 1
#define I2C_BBPLL_IR_CAL_ENX_CAP_MSB 4
#define I2C_BBPLL_IR_CAL_ENX_CAP_LSB 4
#define I2C_BBPLL_IR_CAL_RSTB 1
#define I2C_BBPLL_IR_CAL_RSTB_MSB 5
#define I2C_BBPLL_IR_CAL_RSTB_LSB 5
#define I2C_BBPLL_IR_CAL_START 1
#define I2C_BBPLL_IR_CAL_START_MSB 6
#define I2C_BBPLL_IR_CAL_START_LSB 6
#define I2C_BBPLL_IR_CAL_UNSTOP 1
#define I2C_BBPLL_IR_CAL_UNSTOP_MSB 7
#define I2C_BBPLL_IR_CAL_UNSTOP_LSB 7
#define I2C_BBPLL_OC_REF_DIV 2
#define I2C_BBPLL_OC_REF_DIV_MSB 3
#define I2C_BBPLL_OC_REF_DIV_LSB 0
#define I2C_BBPLL_OC_DCHGP 2
#define I2C_BBPLL_OC_DCHGP_MSB 6
#define I2C_BBPLL_OC_DCHGP_LSB 4
#define I2C_BBPLL_OC_ENB_FCAL 2
#define I2C_BBPLL_OC_ENB_FCAL_MSB 7
#define I2C_BBPLL_OC_ENB_FCAL_LSB 7
#define I2C_BBPLL_OC_DIV_7_0 3
#define I2C_BBPLL_OC_DIV_7_0_MSB 7
#define I2C_BBPLL_OC_DIV_7_0_LSB 0
#define I2C_BBPLL_RSTB_DIV_ADC 4
#define I2C_BBPLL_RSTB_DIV_ADC_MSB 0
#define I2C_BBPLL_RSTB_DIV_ADC_LSB 0
#define I2C_BBPLL_MODE_HF 4
#define I2C_BBPLL_MODE_HF_MSB 1
#define I2C_BBPLL_MODE_HF_LSB 1
#define I2C_BBPLL_DIV_ADC 4
#define I2C_BBPLL_DIV_ADC_MSB 3
#define I2C_BBPLL_DIV_ADC_LSB 2
#define I2C_BBPLL_DIV_DAC 4
#define I2C_BBPLL_DIV_DAC_MSB 4
#define I2C_BBPLL_DIV_DAC_LSB 4
#define I2C_BBPLL_DIV_CPU 4
#define I2C_BBPLL_DIV_CPU_MSB 5
#define I2C_BBPLL_DIV_CPU_LSB 5
#define I2C_BBPLL_OC_ENB_VCON 4
#define I2C_BBPLL_OC_ENB_VCON_MSB 6
#define I2C_BBPLL_OC_ENB_VCON_LSB 6
#define I2C_BBPLL_OC_TSCHGP 4
#define I2C_BBPLL_OC_TSCHGP_MSB 7
#define I2C_BBPLL_OC_TSCHGP_LSB 7
#define I2C_BBPLL_OC_DR1 5
#define I2C_BBPLL_OC_DR1_MSB 2
#define I2C_BBPLL_OC_DR1_LSB 0
#define I2C_BBPLL_OC_DR3 5
#define I2C_BBPLL_OC_DR3_MSB 6
#define I2C_BBPLL_OC_DR3_LSB 4
#define I2C_BBPLL_EN_USB 5
#define I2C_BBPLL_EN_USB_MSB 7
#define I2C_BBPLL_EN_USB_LSB 7
#define I2C_BBPLL_OC_DCUR 6
#define I2C_BBPLL_OC_DCUR_MSB 2
#define I2C_BBPLL_OC_DCUR_LSB 0
#define I2C_BBPLL_INC_CUR 6
#define I2C_BBPLL_INC_CUR_MSB 3
#define I2C_BBPLL_INC_CUR_LSB 3
#define I2C_BBPLL_OC_DHREF_SEL 6
#define I2C_BBPLL_OC_DHREF_SEL_MSB 5
#define I2C_BBPLL_OC_DHREF_SEL_LSB 4
#define I2C_BBPLL_OC_DLREF_SEL 6
#define I2C_BBPLL_OC_DLREF_SEL_MSB 7
#define I2C_BBPLL_OC_DLREF_SEL_LSB 6
#define I2C_BBPLL_OR_CAL_CAP 8
#define I2C_BBPLL_OR_CAL_CAP_MSB 3
#define I2C_BBPLL_OR_CAL_CAP_LSB 0
#define I2C_BBPLL_OR_CAL_UDF 8
#define I2C_BBPLL_OR_CAL_UDF_MSB 4
#define I2C_BBPLL_OR_CAL_UDF_LSB 4
#define I2C_BBPLL_OR_CAL_OVF 8
#define I2C_BBPLL_OR_CAL_OVF_MSB 5
#define I2C_BBPLL_OR_CAL_OVF_LSB 5
#define I2C_BBPLL_OR_CAL_END 8
#define I2C_BBPLL_OR_CAL_END_MSB 6
#define I2C_BBPLL_OR_CAL_END_LSB 6
#define I2C_BBPLL_OR_LOCK 8
#define I2C_BBPLL_OR_LOCK_MSB 7
#define I2C_BBPLL_OR_LOCK_LSB 7
#define I2C_BBPLL_BBADC_DELAY1 9
#define I2C_BBPLL_BBADC_DELAY1_MSB 1
#define I2C_BBPLL_BBADC_DELAY1_LSB 0
#define I2C_BBPLL_BBADC_DELAY2 9
#define I2C_BBPLL_BBADC_DELAY2_MSB 3
#define I2C_BBPLL_BBADC_DELAY2_LSB 2
#define I2C_BBPLL_BBADC_DVDD 9
#define I2C_BBPLL_BBADC_DVDD_MSB 5
#define I2C_BBPLL_BBADC_DVDD_LSB 4
#define I2C_BBPLL_BBADC_DREF 9
#define I2C_BBPLL_BBADC_DREF_MSB 7
#define I2C_BBPLL_BBADC_DREF_LSB 6
#define I2C_BBPLL_BBADC_DCUR 10
#define I2C_BBPLL_BBADC_DCUR_MSB 1
#define I2C_BBPLL_BBADC_DCUR_LSB 0
#define I2C_BBPLL_BBADC_INPUT_SHORT 10
#define I2C_BBPLL_BBADC_INPUT_SHORT_MSB 2
#define I2C_BBPLL_BBADC_INPUT_SHORT_LSB 2
#define I2C_BBPLL_ENT_PLL 10
#define I2C_BBPLL_ENT_PLL_MSB 3
#define I2C_BBPLL_ENT_PLL_LSB 3
#define I2C_BBPLL_DTEST 10
#define I2C_BBPLL_DTEST_MSB 5
#define I2C_BBPLL_DTEST_LSB 4
#define I2C_BBPLL_ENT_ADC 10
#define I2C_BBPLL_ENT_ADC_MSB 7
#define I2C_BBPLL_ENT_ADC_LSB 6

View File

@ -0,0 +1,30 @@
// 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/i2c_periph.h"
#include "soc/gpio_sig_map.h"
/*
Bunch of constants for every I2C peripheral: GPIO signals, irqs, hw addr of registers etc
*/
const i2c_signal_conn_t i2c_periph_signal[SOC_I2C_NUM] = {
{
.sda_out_sig = I2CEXT0_SDA_OUT_IDX,
.sda_in_sig = I2CEXT0_SDA_IN_IDX,
.scl_out_sig = I2CEXT0_SCL_OUT_IDX,
.scl_in_sig = I2CEXT0_SCL_IN_IDX,
.irq = ETS_I2C_EXT0_INTR_SOURCE,
.module = PERIPH_I2C0_MODULE,
},
};

View File

@ -0,0 +1,38 @@
// 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/i2s_periph.h"
#include "soc/gpio_sig_map.h"
/*
Bunch of constants for every I2S peripheral: GPIO signals, irqs, hw addr of registers etc
*/
const i2s_signal_conn_t i2s_periph_signal[SOC_I2S_NUM] = {
{
// TODO ESP32-C3 IDF-2098
// .o_bck_in_sig = I2S0O_BCK_IN_IDX,
// .o_ws_in_sig = I2S0O_WS_IN_IDX,
// .o_bck_out_sig = I2S0O_BCK_OUT_IDX,
// .o_ws_out_sig = I2S0O_WS_OUT_IDX,
// .o_data_out_sig = I2S0O_SD_OUT_IDX,
// .i_bck_in_sig = I2S0I_BCK_OUT_IDX,
// .i_ws_in_sig = I2S0I_WS_OUT_IDX,
// .i_bck_out_sig = I2S0I_BCK_IN_IDX,
// .i_ws_out_sig = I2S0I_WS_IN_IDX,
// .i_data_in_sig = I2S0I_SD_IN_IDX,
.irq = ETS_I2S1_INTR_SOURCE,
.module = PERIPH_I2S1_MODULE,
}
};

View File

@ -0,0 +1,36 @@
// 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.
#ifndef _SOC_ADC_CHANNEL_H
#define _SOC_ADC_CHANNEL_H
#define ADC1_GPIO1_CHANNEL ADC1_CHANNEL_0
#define ADC1_CHANNEL_0_GPIO_NUM 0
#define ADC1_GPIO2_CHANNEL ADC1_CHANNEL_1
#define ADC1_CHANNEL_1_GPIO_NUM 1
#define ADC1_GPIO3_CHANNEL ADC1_CHANNEL_2
#define ADC1_CHANNEL_2_GPIO_NUM 2
#define ADC1_GPIO4_CHANNEL ADC1_CHANNEL_3
#define ADC1_CHANNEL_3_GPIO_NUM 3
#define ADC1_GPIO5_CHANNEL ADC1_CHANNEL_4
#define ADC1_CHANNEL_4_GPIO_NUM 4
#define ADC2_GPIO5_CHANNEL ADC2_CHANNEL_0
#define ADC2_CHANNEL_0_GPIO_NUM 5
#endif

View File

@ -0,0 +1,576 @@
// 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.
#ifndef _SOC_APB_CTRL_REG_H_
#define _SOC_APB_CTRL_REG_H_
#ifdef __cplusplus
extern "C" {
#endif
#include "soc.h"
#define APB_CTRL_SYSCLK_CONF_REG (DR_REG_APB_CTRL_BASE + 0x000)
/* APB_CTRL_RST_TICK_CNT : R/W ;bitpos:[12] ;default: 1'b0 ; */
/*description: */
#define APB_CTRL_RST_TICK_CNT (BIT(12))
#define APB_CTRL_RST_TICK_CNT_M (BIT(12))
#define APB_CTRL_RST_TICK_CNT_V 0x1
#define APB_CTRL_RST_TICK_CNT_S 12
/* APB_CTRL_CLK_EN : R/W ;bitpos:[11] ;default: 1'b0 ; */
/*description: */
#define APB_CTRL_CLK_EN (BIT(11))
#define APB_CTRL_CLK_EN_M (BIT(11))
#define APB_CTRL_CLK_EN_V 0x1
#define APB_CTRL_CLK_EN_S 11
/* APB_CTRL_CLK_320M_EN : R/W ;bitpos:[10] ;default: 1'b0 ; */
/*description: */
#define APB_CTRL_CLK_320M_EN (BIT(10))
#define APB_CTRL_CLK_320M_EN_M (BIT(10))
#define APB_CTRL_CLK_320M_EN_V 0x1
#define APB_CTRL_CLK_320M_EN_S 10
/* APB_CTRL_PRE_DIV_CNT : R/W ;bitpos:[9:0] ;default: 10'h1 ; */
/*description: */
#define APB_CTRL_PRE_DIV_CNT 0x000003FF
#define APB_CTRL_PRE_DIV_CNT_M ((APB_CTRL_PRE_DIV_CNT_V)<<(APB_CTRL_PRE_DIV_CNT_S))
#define APB_CTRL_PRE_DIV_CNT_V 0x3FF
#define APB_CTRL_PRE_DIV_CNT_S 0
#define APB_CTRL_TICK_CONF_REG (DR_REG_APB_CTRL_BASE + 0x004)
/* APB_CTRL_TICK_ENABLE : R/W ;bitpos:[16] ;default: 1'd1 ; */
/*description: */
#define APB_CTRL_TICK_ENABLE (BIT(16))
#define APB_CTRL_TICK_ENABLE_M (BIT(16))
#define APB_CTRL_TICK_ENABLE_V 0x1
#define APB_CTRL_TICK_ENABLE_S 16
/* APB_CTRL_CK8M_TICK_NUM : R/W ;bitpos:[15:8] ;default: 8'd7 ; */
/*description: */
#define APB_CTRL_CK8M_TICK_NUM 0x000000FF
#define APB_CTRL_CK8M_TICK_NUM_M ((APB_CTRL_CK8M_TICK_NUM_V)<<(APB_CTRL_CK8M_TICK_NUM_S))
#define APB_CTRL_CK8M_TICK_NUM_V 0xFF
#define APB_CTRL_CK8M_TICK_NUM_S 8
/* APB_CTRL_XTAL_TICK_NUM : R/W ;bitpos:[7:0] ;default: 8'd39 ; */
/*description: */
#define APB_CTRL_XTAL_TICK_NUM 0x000000FF
#define APB_CTRL_XTAL_TICK_NUM_M ((APB_CTRL_XTAL_TICK_NUM_V)<<(APB_CTRL_XTAL_TICK_NUM_S))
#define APB_CTRL_XTAL_TICK_NUM_V 0xFF
#define APB_CTRL_XTAL_TICK_NUM_S 0
#define APB_CTRL_CLK_OUT_EN_REG (DR_REG_APB_CTRL_BASE + 0x008)
/* APB_CTRL_CLK_XTAL_OEN : R/W ;bitpos:[10] ;default: 1'b1 ; */
/*description: */
#define APB_CTRL_CLK_XTAL_OEN (BIT(10))
#define APB_CTRL_CLK_XTAL_OEN_M (BIT(10))
#define APB_CTRL_CLK_XTAL_OEN_V 0x1
#define APB_CTRL_CLK_XTAL_OEN_S 10
/* APB_CTRL_CLK40X_BB_OEN : R/W ;bitpos:[9] ;default: 1'b1 ; */
/*description: */
#define APB_CTRL_CLK40X_BB_OEN (BIT(9))
#define APB_CTRL_CLK40X_BB_OEN_M (BIT(9))
#define APB_CTRL_CLK40X_BB_OEN_V 0x1
#define APB_CTRL_CLK40X_BB_OEN_S 9
/* APB_CTRL_CLK_DAC_CPU_OEN : R/W ;bitpos:[8] ;default: 1'b1 ; */
/*description: */
#define APB_CTRL_CLK_DAC_CPU_OEN (BIT(8))
#define APB_CTRL_CLK_DAC_CPU_OEN_M (BIT(8))
#define APB_CTRL_CLK_DAC_CPU_OEN_V 0x1
#define APB_CTRL_CLK_DAC_CPU_OEN_S 8
/* APB_CTRL_CLK_ADC_INF_OEN : R/W ;bitpos:[7] ;default: 1'b1 ; */
/*description: */
#define APB_CTRL_CLK_ADC_INF_OEN (BIT(7))
#define APB_CTRL_CLK_ADC_INF_OEN_M (BIT(7))
#define APB_CTRL_CLK_ADC_INF_OEN_V 0x1
#define APB_CTRL_CLK_ADC_INF_OEN_S 7
/* APB_CTRL_CLK_320M_OEN : R/W ;bitpos:[6] ;default: 1'b1 ; */
/*description: */
#define APB_CTRL_CLK_320M_OEN (BIT(6))
#define APB_CTRL_CLK_320M_OEN_M (BIT(6))
#define APB_CTRL_CLK_320M_OEN_V 0x1
#define APB_CTRL_CLK_320M_OEN_S 6
/* APB_CTRL_CLK160_OEN : R/W ;bitpos:[5] ;default: 1'b1 ; */
/*description: */
#define APB_CTRL_CLK160_OEN (BIT(5))
#define APB_CTRL_CLK160_OEN_M (BIT(5))
#define APB_CTRL_CLK160_OEN_V 0x1
#define APB_CTRL_CLK160_OEN_S 5
/* APB_CTRL_CLK80_OEN : R/W ;bitpos:[4] ;default: 1'b1 ; */
/*description: */
#define APB_CTRL_CLK80_OEN (BIT(4))
#define APB_CTRL_CLK80_OEN_M (BIT(4))
#define APB_CTRL_CLK80_OEN_V 0x1
#define APB_CTRL_CLK80_OEN_S 4
/* APB_CTRL_CLK_BB_OEN : R/W ;bitpos:[3] ;default: 1'b1 ; */
/*description: */
#define APB_CTRL_CLK_BB_OEN (BIT(3))
#define APB_CTRL_CLK_BB_OEN_M (BIT(3))
#define APB_CTRL_CLK_BB_OEN_V 0x1
#define APB_CTRL_CLK_BB_OEN_S 3
/* APB_CTRL_CLK44_OEN : R/W ;bitpos:[2] ;default: 1'b1 ; */
/*description: */
#define APB_CTRL_CLK44_OEN (BIT(2))
#define APB_CTRL_CLK44_OEN_M (BIT(2))
#define APB_CTRL_CLK44_OEN_V 0x1
#define APB_CTRL_CLK44_OEN_S 2
/* APB_CTRL_CLK22_OEN : R/W ;bitpos:[1] ;default: 1'b1 ; */
/*description: */
#define APB_CTRL_CLK22_OEN (BIT(1))
#define APB_CTRL_CLK22_OEN_M (BIT(1))
#define APB_CTRL_CLK22_OEN_V 0x1
#define APB_CTRL_CLK22_OEN_S 1
/* APB_CTRL_CLK20_OEN : R/W ;bitpos:[0] ;default: 1'b1 ; */
/*description: */
#define APB_CTRL_CLK20_OEN (BIT(0))
#define APB_CTRL_CLK20_OEN_M (BIT(0))
#define APB_CTRL_CLK20_OEN_V 0x1
#define APB_CTRL_CLK20_OEN_S 0
#define APB_CTRL_WIFI_BB_CFG_REG (DR_REG_APB_CTRL_BASE + 0x00C)
/* APB_CTRL_WIFI_BB_CFG : R/W ;bitpos:[31:0] ;default: 32'h0 ; */
/*description: */
#define APB_CTRL_WIFI_BB_CFG 0xFFFFFFFF
#define APB_CTRL_WIFI_BB_CFG_M ((APB_CTRL_WIFI_BB_CFG_V)<<(APB_CTRL_WIFI_BB_CFG_S))
#define APB_CTRL_WIFI_BB_CFG_V 0xFFFFFFFF
#define APB_CTRL_WIFI_BB_CFG_S 0
#define APB_CTRL_WIFI_BB_CFG_2_REG (DR_REG_APB_CTRL_BASE + 0x010)
/* APB_CTRL_WIFI_BB_CFG_2 : R/W ;bitpos:[31:0] ;default: 32'h0 ; */
/*description: */
#define APB_CTRL_WIFI_BB_CFG_2 0xFFFFFFFF
#define APB_CTRL_WIFI_BB_CFG_2_M ((APB_CTRL_WIFI_BB_CFG_2_V)<<(APB_CTRL_WIFI_BB_CFG_2_S))
#define APB_CTRL_WIFI_BB_CFG_2_V 0xFFFFFFFF
#define APB_CTRL_WIFI_BB_CFG_2_S 0
#define APB_CTRL_WIFI_CLK_EN_REG (DR_REG_APB_CTRL_BASE + 0x014)
/* APB_CTRL_WIFI_CLK_EN : R/W ;bitpos:[31:0] ;default: 32'hfffce030 ; */
/*description: */
#define APB_CTRL_WIFI_CLK_EN 0xFFFFFFFF
#define APB_CTRL_WIFI_CLK_EN_M ((APB_CTRL_WIFI_CLK_EN_V)<<(APB_CTRL_WIFI_CLK_EN_S))
#define APB_CTRL_WIFI_CLK_EN_V 0xFFFFFFFF
#define APB_CTRL_WIFI_CLK_EN_S 0
#define APB_CTRL_WIFI_RST_EN_REG (DR_REG_APB_CTRL_BASE + 0x018)
/* APB_CTRL_WIFI_RST : R/W ;bitpos:[31:0] ;default: 32'h0 ; */
/*description: */
#define APB_CTRL_WIFI_RST 0xFFFFFFFF
#define APB_CTRL_WIFI_RST_M ((APB_CTRL_WIFI_RST_V)<<(APB_CTRL_WIFI_RST_S))
#define APB_CTRL_WIFI_RST_V 0xFFFFFFFF
#define APB_CTRL_WIFI_RST_S 0
#define APB_CTRL_HOST_INF_SEL_REG (DR_REG_APB_CTRL_BASE + 0x01C)
/* APB_CTRL_PERI_IO_SWAP : R/W ;bitpos:[7:0] ;default: 8'h0 ; */
/*description: */
#define APB_CTRL_PERI_IO_SWAP 0x000000FF
#define APB_CTRL_PERI_IO_SWAP_M ((APB_CTRL_PERI_IO_SWAP_V)<<(APB_CTRL_PERI_IO_SWAP_S))
#define APB_CTRL_PERI_IO_SWAP_V 0xFF
#define APB_CTRL_PERI_IO_SWAP_S 0
#define APB_CTRL_EXT_MEM_PMS_LOCK_REG (DR_REG_APB_CTRL_BASE + 0x020)
/* APB_CTRL_EXT_MEM_PMS_LOCK : R/W ;bitpos:[0] ;default: 1'b0 ; */
/*description: */
#define APB_CTRL_EXT_MEM_PMS_LOCK (BIT(0))
#define APB_CTRL_EXT_MEM_PMS_LOCK_M (BIT(0))
#define APB_CTRL_EXT_MEM_PMS_LOCK_V 0x1
#define APB_CTRL_EXT_MEM_PMS_LOCK_S 0
#define APB_CTRL_FLASH_ACE0_ATTR_REG (DR_REG_APB_CTRL_BASE + 0x028)
/* APB_CTRL_FLASH_ACE0_ATTR : R/W ;bitpos:[1:0] ;default: 2'h3 ; */
/*description: */
#define APB_CTRL_FLASH_ACE0_ATTR 0x00000003
#define APB_CTRL_FLASH_ACE0_ATTR_M ((APB_CTRL_FLASH_ACE0_ATTR_V)<<(APB_CTRL_FLASH_ACE0_ATTR_S))
#define APB_CTRL_FLASH_ACE0_ATTR_V 0x3
#define APB_CTRL_FLASH_ACE0_ATTR_S 0
#define APB_CTRL_FLASH_ACE1_ATTR_REG (DR_REG_APB_CTRL_BASE + 0x02C)
/* APB_CTRL_FLASH_ACE1_ATTR : R/W ;bitpos:[1:0] ;default: 2'h3 ; */
/*description: */
#define APB_CTRL_FLASH_ACE1_ATTR 0x00000003
#define APB_CTRL_FLASH_ACE1_ATTR_M ((APB_CTRL_FLASH_ACE1_ATTR_V)<<(APB_CTRL_FLASH_ACE1_ATTR_S))
#define APB_CTRL_FLASH_ACE1_ATTR_V 0x3
#define APB_CTRL_FLASH_ACE1_ATTR_S 0
#define APB_CTRL_FLASH_ACE2_ATTR_REG (DR_REG_APB_CTRL_BASE + 0x030)
/* APB_CTRL_FLASH_ACE2_ATTR : R/W ;bitpos:[1:0] ;default: 2'h3 ; */
/*description: */
#define APB_CTRL_FLASH_ACE2_ATTR 0x00000003
#define APB_CTRL_FLASH_ACE2_ATTR_M ((APB_CTRL_FLASH_ACE2_ATTR_V)<<(APB_CTRL_FLASH_ACE2_ATTR_S))
#define APB_CTRL_FLASH_ACE2_ATTR_V 0x3
#define APB_CTRL_FLASH_ACE2_ATTR_S 0
#define APB_CTRL_FLASH_ACE3_ATTR_REG (DR_REG_APB_CTRL_BASE + 0x034)
/* APB_CTRL_FLASH_ACE3_ATTR : R/W ;bitpos:[1:0] ;default: 2'h3 ; */
/*description: */
#define APB_CTRL_FLASH_ACE3_ATTR 0x00000003
#define APB_CTRL_FLASH_ACE3_ATTR_M ((APB_CTRL_FLASH_ACE3_ATTR_V)<<(APB_CTRL_FLASH_ACE3_ATTR_S))
#define APB_CTRL_FLASH_ACE3_ATTR_V 0x3
#define APB_CTRL_FLASH_ACE3_ATTR_S 0
#define APB_CTRL_FLASH_ACE0_ADDR_REG (DR_REG_APB_CTRL_BASE + 0x038)
/* APB_CTRL_FLASH_ACE0_ADDR_S : R/W ;bitpos:[31:0] ;default: 32'h0 ; */
/*description: */
#define APB_CTRL_FLASH_ACE0_ADDR_S 0xFFFFFFFF
#define APB_CTRL_FLASH_ACE0_ADDR_S_M ((APB_CTRL_FLASH_ACE0_ADDR_S_V)<<(APB_CTRL_FLASH_ACE0_ADDR_S_S))
#define APB_CTRL_FLASH_ACE0_ADDR_S_V 0xFFFFFFFF
#define APB_CTRL_FLASH_ACE0_ADDR_S_S 0
#define APB_CTRL_FLASH_ACE1_ADDR_REG (DR_REG_APB_CTRL_BASE + 0x03C)
/* APB_CTRL_FLASH_ACE1_ADDR_S : R/W ;bitpos:[31:0] ;default: 32'h400000 ; */
/*description: */
#define APB_CTRL_FLASH_ACE1_ADDR_S 0xFFFFFFFF
#define APB_CTRL_FLASH_ACE1_ADDR_S_M ((APB_CTRL_FLASH_ACE1_ADDR_S_V)<<(APB_CTRL_FLASH_ACE1_ADDR_S_S))
#define APB_CTRL_FLASH_ACE1_ADDR_S_V 0xFFFFFFFF
#define APB_CTRL_FLASH_ACE1_ADDR_S_S 0
#define APB_CTRL_FLASH_ACE2_ADDR_REG (DR_REG_APB_CTRL_BASE + 0x040)
/* APB_CTRL_FLASH_ACE2_ADDR_S : R/W ;bitpos:[31:0] ;default: 32'h800000 ; */
/*description: */
#define APB_CTRL_FLASH_ACE2_ADDR_S 0xFFFFFFFF
#define APB_CTRL_FLASH_ACE2_ADDR_S_M ((APB_CTRL_FLASH_ACE2_ADDR_S_V)<<(APB_CTRL_FLASH_ACE2_ADDR_S_S))
#define APB_CTRL_FLASH_ACE2_ADDR_S_V 0xFFFFFFFF
#define APB_CTRL_FLASH_ACE2_ADDR_S_S 0
#define APB_CTRL_FLASH_ACE3_ADDR_REG (DR_REG_APB_CTRL_BASE + 0x044)
/* APB_CTRL_FLASH_ACE3_ADDR_S : R/W ;bitpos:[31:0] ;default: 32'hC00000 ; */
/*description: */
#define APB_CTRL_FLASH_ACE3_ADDR_S 0xFFFFFFFF
#define APB_CTRL_FLASH_ACE3_ADDR_S_M ((APB_CTRL_FLASH_ACE3_ADDR_S_V)<<(APB_CTRL_FLASH_ACE3_ADDR_S_S))
#define APB_CTRL_FLASH_ACE3_ADDR_S_V 0xFFFFFFFF
#define APB_CTRL_FLASH_ACE3_ADDR_S_S 0
#define APB_CTRL_FLASH_ACE0_SIZE_REG (DR_REG_APB_CTRL_BASE + 0x048)
/* APB_CTRL_FLASH_ACE0_SIZE : R/W ;bitpos:[12:0] ;default: 13'h400 ; */
/*description: */
#define APB_CTRL_FLASH_ACE0_SIZE 0x00001FFF
#define APB_CTRL_FLASH_ACE0_SIZE_M ((APB_CTRL_FLASH_ACE0_SIZE_V)<<(APB_CTRL_FLASH_ACE0_SIZE_S))
#define APB_CTRL_FLASH_ACE0_SIZE_V 0x1FFF
#define APB_CTRL_FLASH_ACE0_SIZE_S 0
#define APB_CTRL_FLASH_ACE1_SIZE_REG (DR_REG_APB_CTRL_BASE + 0x04C)
/* APB_CTRL_FLASH_ACE1_SIZE : R/W ;bitpos:[12:0] ;default: 13'h400 ; */
/*description: */
#define APB_CTRL_FLASH_ACE1_SIZE 0x00001FFF
#define APB_CTRL_FLASH_ACE1_SIZE_M ((APB_CTRL_FLASH_ACE1_SIZE_V)<<(APB_CTRL_FLASH_ACE1_SIZE_S))
#define APB_CTRL_FLASH_ACE1_SIZE_V 0x1FFF
#define APB_CTRL_FLASH_ACE1_SIZE_S 0
#define APB_CTRL_FLASH_ACE2_SIZE_REG (DR_REG_APB_CTRL_BASE + 0x050)
/* APB_CTRL_FLASH_ACE2_SIZE : R/W ;bitpos:[12:0] ;default: 13'h400 ; */
/*description: */
#define APB_CTRL_FLASH_ACE2_SIZE 0x00001FFF
#define APB_CTRL_FLASH_ACE2_SIZE_M ((APB_CTRL_FLASH_ACE2_SIZE_V)<<(APB_CTRL_FLASH_ACE2_SIZE_S))
#define APB_CTRL_FLASH_ACE2_SIZE_V 0x1FFF
#define APB_CTRL_FLASH_ACE2_SIZE_S 0
#define APB_CTRL_FLASH_ACE3_SIZE_REG (DR_REG_APB_CTRL_BASE + 0x054)
/* APB_CTRL_FLASH_ACE3_SIZE : R/W ;bitpos:[12:0] ;default: 13'h400 ; */
/*description: */
#define APB_CTRL_FLASH_ACE3_SIZE 0x00001FFF
#define APB_CTRL_FLASH_ACE3_SIZE_M ((APB_CTRL_FLASH_ACE3_SIZE_V)<<(APB_CTRL_FLASH_ACE3_SIZE_S))
#define APB_CTRL_FLASH_ACE3_SIZE_V 0x1FFF
#define APB_CTRL_FLASH_ACE3_SIZE_S 0
#define APB_CTRL_SPI_MEM_PMS_CTRL_REG (DR_REG_APB_CTRL_BASE + 0x088)
/* APB_CTRL_SPI_MEM_REJECT_CDE : RO ;bitpos:[6:2] ;default: 5'h0 ; */
/*description: */
#define APB_CTRL_SPI_MEM_REJECT_CDE 0x0000001F
#define APB_CTRL_SPI_MEM_REJECT_CDE_M ((APB_CTRL_SPI_MEM_REJECT_CDE_V)<<(APB_CTRL_SPI_MEM_REJECT_CDE_S))
#define APB_CTRL_SPI_MEM_REJECT_CDE_V 0x1F
#define APB_CTRL_SPI_MEM_REJECT_CDE_S 2
/* APB_CTRL_SPI_MEM_REJECT_CLR : WOD ;bitpos:[1] ;default: 1'b0 ; */
/*description: */
#define APB_CTRL_SPI_MEM_REJECT_CLR (BIT(1))
#define APB_CTRL_SPI_MEM_REJECT_CLR_M (BIT(1))
#define APB_CTRL_SPI_MEM_REJECT_CLR_V 0x1
#define APB_CTRL_SPI_MEM_REJECT_CLR_S 1
/* APB_CTRL_SPI_MEM_REJECT_INT : RO ;bitpos:[0] ;default: 1'b0 ; */
/*description: */
#define APB_CTRL_SPI_MEM_REJECT_INT (BIT(0))
#define APB_CTRL_SPI_MEM_REJECT_INT_M (BIT(0))
#define APB_CTRL_SPI_MEM_REJECT_INT_V 0x1
#define APB_CTRL_SPI_MEM_REJECT_INT_S 0
#define APB_CTRL_SPI_MEM_REJECT_ADDR_REG (DR_REG_APB_CTRL_BASE + 0x08C)
/* APB_CTRL_SPI_MEM_REJECT_ADDR : RO ;bitpos:[31:0] ;default: 32'h0 ; */
/*description: */
#define APB_CTRL_SPI_MEM_REJECT_ADDR 0xFFFFFFFF
#define APB_CTRL_SPI_MEM_REJECT_ADDR_M ((APB_CTRL_SPI_MEM_REJECT_ADDR_V)<<(APB_CTRL_SPI_MEM_REJECT_ADDR_S))
#define APB_CTRL_SPI_MEM_REJECT_ADDR_V 0xFFFFFFFF
#define APB_CTRL_SPI_MEM_REJECT_ADDR_S 0
#define APB_CTRL_SDIO_CTRL_REG (DR_REG_APB_CTRL_BASE + 0x090)
/* APB_CTRL_SDIO_WIN_ACCESS_EN : R/W ;bitpos:[0] ;default: 1'h0 ; */
/*description: */
#define APB_CTRL_SDIO_WIN_ACCESS_EN (BIT(0))
#define APB_CTRL_SDIO_WIN_ACCESS_EN_M (BIT(0))
#define APB_CTRL_SDIO_WIN_ACCESS_EN_V 0x1
#define APB_CTRL_SDIO_WIN_ACCESS_EN_S 0
#define APB_CTRL_REDCY_SIG0_REG (DR_REG_APB_CTRL_BASE + 0x094)
/* APB_CTRL_REDCY_ANDOR : RO ;bitpos:[31] ;default: 1'h0 ; */
/*description: */
#define APB_CTRL_REDCY_ANDOR (BIT(31))
#define APB_CTRL_REDCY_ANDOR_M (BIT(31))
#define APB_CTRL_REDCY_ANDOR_V 0x1
#define APB_CTRL_REDCY_ANDOR_S 31
/* APB_CTRL_REDCY_SIG0 : R/W ;bitpos:[30:0] ;default: 31'h0 ; */
/*description: */
#define APB_CTRL_REDCY_SIG0 0x7FFFFFFF
#define APB_CTRL_REDCY_SIG0_M ((APB_CTRL_REDCY_SIG0_V)<<(APB_CTRL_REDCY_SIG0_S))
#define APB_CTRL_REDCY_SIG0_V 0x7FFFFFFF
#define APB_CTRL_REDCY_SIG0_S 0
#define APB_CTRL_REDCY_SIG1_REG (DR_REG_APB_CTRL_BASE + 0x098)
/* APB_CTRL_REDCY_NANDOR : RO ;bitpos:[31] ;default: 1'h0 ; */
/*description: */
#define APB_CTRL_REDCY_NANDOR (BIT(31))
#define APB_CTRL_REDCY_NANDOR_M (BIT(31))
#define APB_CTRL_REDCY_NANDOR_V 0x1
#define APB_CTRL_REDCY_NANDOR_S 31
/* APB_CTRL_REDCY_SIG1 : R/W ;bitpos:[30:0] ;default: 31'h0 ; */
/*description: */
#define APB_CTRL_REDCY_SIG1 0x7FFFFFFF
#define APB_CTRL_REDCY_SIG1_M ((APB_CTRL_REDCY_SIG1_V)<<(APB_CTRL_REDCY_SIG1_S))
#define APB_CTRL_REDCY_SIG1_V 0x7FFFFFFF
#define APB_CTRL_REDCY_SIG1_S 0
#define APB_CTRL_FRONT_END_MEM_PD_REG (DR_REG_APB_CTRL_BASE + 0x09C)
/* APB_CTRL_DC_MEM_FORCE_PD : R/W ;bitpos:[5] ;default: 1'b0 ; */
/*description: */
#define APB_CTRL_DC_MEM_FORCE_PD (BIT(5))
#define APB_CTRL_DC_MEM_FORCE_PD_M (BIT(5))
#define APB_CTRL_DC_MEM_FORCE_PD_V 0x1
#define APB_CTRL_DC_MEM_FORCE_PD_S 5
/* APB_CTRL_DC_MEM_FORCE_PU : R/W ;bitpos:[4] ;default: 1'b1 ; */
/*description: */
#define APB_CTRL_DC_MEM_FORCE_PU (BIT(4))
#define APB_CTRL_DC_MEM_FORCE_PU_M (BIT(4))
#define APB_CTRL_DC_MEM_FORCE_PU_V 0x1
#define APB_CTRL_DC_MEM_FORCE_PU_S 4
/* APB_CTRL_PBUS_MEM_FORCE_PD : R/W ;bitpos:[3] ;default: 1'b0 ; */
/*description: */
#define APB_CTRL_PBUS_MEM_FORCE_PD (BIT(3))
#define APB_CTRL_PBUS_MEM_FORCE_PD_M (BIT(3))
#define APB_CTRL_PBUS_MEM_FORCE_PD_V 0x1
#define APB_CTRL_PBUS_MEM_FORCE_PD_S 3
/* APB_CTRL_PBUS_MEM_FORCE_PU : R/W ;bitpos:[2] ;default: 1'b1 ; */
/*description: */
#define APB_CTRL_PBUS_MEM_FORCE_PU (BIT(2))
#define APB_CTRL_PBUS_MEM_FORCE_PU_M (BIT(2))
#define APB_CTRL_PBUS_MEM_FORCE_PU_V 0x1
#define APB_CTRL_PBUS_MEM_FORCE_PU_S 2
/* APB_CTRL_AGC_MEM_FORCE_PD : R/W ;bitpos:[1] ;default: 1'b0 ; */
/*description: */
#define APB_CTRL_AGC_MEM_FORCE_PD (BIT(1))
#define APB_CTRL_AGC_MEM_FORCE_PD_M (BIT(1))
#define APB_CTRL_AGC_MEM_FORCE_PD_V 0x1
#define APB_CTRL_AGC_MEM_FORCE_PD_S 1
/* APB_CTRL_AGC_MEM_FORCE_PU : R/W ;bitpos:[0] ;default: 1'b1 ; */
/*description: */
#define APB_CTRL_AGC_MEM_FORCE_PU (BIT(0))
#define APB_CTRL_AGC_MEM_FORCE_PU_M (BIT(0))
#define APB_CTRL_AGC_MEM_FORCE_PU_V 0x1
#define APB_CTRL_AGC_MEM_FORCE_PU_S 0
#define APB_CTRL_RETENTION_CTRL_REG (DR_REG_APB_CTRL_BASE + 0x0A0)
/* APB_CTRL_NOBYPASS_CPU_ISO_RST : R/W ;bitpos:[27] ;default: 1'b0 ; */
/*description: */
#define APB_CTRL_NOBYPASS_CPU_ISO_RST (BIT(27))
#define APB_CTRL_NOBYPASS_CPU_ISO_RST_M (BIT(27))
#define APB_CTRL_NOBYPASS_CPU_ISO_RST_V 0x1
#define APB_CTRL_NOBYPASS_CPU_ISO_RST_S 27
/* APB_CTRL_RETENTION_LINK_ADDR : R/W ;bitpos:[26:0] ;default: 27'd0 ; */
/*description: */
#define APB_CTRL_RETENTION_LINK_ADDR 0x07FFFFFF
#define APB_CTRL_RETENTION_LINK_ADDR_M ((APB_CTRL_RETENTION_LINK_ADDR_V)<<(APB_CTRL_RETENTION_LINK_ADDR_S))
#define APB_CTRL_RETENTION_LINK_ADDR_V 0x7FFFFFF
#define APB_CTRL_RETENTION_LINK_ADDR_S 0
#define APB_CTRL_CLKGATE_FORCE_ON_REG (DR_REG_APB_CTRL_BASE + 0x0A4)
/* APB_CTRL_SRAM_CLKGATE_FORCE_ON : R/W ;bitpos:[5:2] ;default: ~4'b0 ; */
/*description: */
#define APB_CTRL_SRAM_CLKGATE_FORCE_ON 0x0000000F
#define APB_CTRL_SRAM_CLKGATE_FORCE_ON_M ((APB_CTRL_SRAM_CLKGATE_FORCE_ON_V)<<(APB_CTRL_SRAM_CLKGATE_FORCE_ON_S))
#define APB_CTRL_SRAM_CLKGATE_FORCE_ON_V 0xF
#define APB_CTRL_SRAM_CLKGATE_FORCE_ON_S 2
/* APB_CTRL_ROM_CLKGATE_FORCE_ON : R/W ;bitpos:[1:0] ;default: ~2'b0 ; */
/*description: */
#define APB_CTRL_ROM_CLKGATE_FORCE_ON 0x00000003
#define APB_CTRL_ROM_CLKGATE_FORCE_ON_M ((APB_CTRL_ROM_CLKGATE_FORCE_ON_V)<<(APB_CTRL_ROM_CLKGATE_FORCE_ON_S))
#define APB_CTRL_ROM_CLKGATE_FORCE_ON_V 0x3
#define APB_CTRL_ROM_CLKGATE_FORCE_ON_S 0
#define APB_CTRL_MEM_POWER_DOWN_REG (DR_REG_APB_CTRL_BASE + 0x0A8)
/* APB_CTRL_SRAM_POWER_DOWN : R/W ;bitpos:[5:2] ;default: 4'b0 ; */
/*description: */
#define APB_CTRL_SRAM_POWER_DOWN 0x0000000F
#define APB_CTRL_SRAM_POWER_DOWN_M ((APB_CTRL_SRAM_POWER_DOWN_V)<<(APB_CTRL_SRAM_POWER_DOWN_S))
#define APB_CTRL_SRAM_POWER_DOWN_V 0xF
#define APB_CTRL_SRAM_POWER_DOWN_S 2
/* APB_CTRL_ROM_POWER_DOWN : R/W ;bitpos:[1:0] ;default: 2'b0 ; */
/*description: */
#define APB_CTRL_ROM_POWER_DOWN 0x00000003
#define APB_CTRL_ROM_POWER_DOWN_M ((APB_CTRL_ROM_POWER_DOWN_V)<<(APB_CTRL_ROM_POWER_DOWN_S))
#define APB_CTRL_ROM_POWER_DOWN_V 0x3
#define APB_CTRL_ROM_POWER_DOWN_S 0
#define APB_CTRL_MEM_POWER_UP_REG (DR_REG_APB_CTRL_BASE + 0x0AC)
/* APB_CTRL_SRAM_POWER_UP : R/W ;bitpos:[5:2] ;default: ~4'b0 ; */
/*description: */
#define APB_CTRL_SRAM_POWER_UP 0x0000000F
#define APB_CTRL_SRAM_POWER_UP_M ((APB_CTRL_SRAM_POWER_UP_V)<<(APB_CTRL_SRAM_POWER_UP_S))
#define APB_CTRL_SRAM_POWER_UP_V 0xF
#define APB_CTRL_SRAM_POWER_UP_S 2
/* APB_CTRL_ROM_POWER_UP : R/W ;bitpos:[1:0] ;default: ~2'b0 ; */
/*description: */
#define APB_CTRL_ROM_POWER_UP 0x00000003
#define APB_CTRL_ROM_POWER_UP_M ((APB_CTRL_ROM_POWER_UP_V)<<(APB_CTRL_ROM_POWER_UP_S))
#define APB_CTRL_ROM_POWER_UP_V 0x3
#define APB_CTRL_ROM_POWER_UP_S 0
#define APB_CTRL_RND_DATA_REG (DR_REG_APB_CTRL_BASE + 0x0B0)
/* APB_CTRL_RND_DATA : RO ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define APB_CTRL_RND_DATA 0xFFFFFFFF
#define APB_CTRL_RND_DATA_M ((APB_CTRL_RND_DATA_V)<<(APB_CTRL_RND_DATA_S))
#define APB_CTRL_RND_DATA_V 0xFFFFFFFF
#define APB_CTRL_RND_DATA_S 0
#define APB_CTRL_PERI_BACKUP_CONFIG_REG (DR_REG_APB_CTRL_BASE + 0x0B4)
/* APB_CTRL_PERI_BACKUP_ENA : R/W ;bitpos:[31] ;default: 1'b0 ; */
/*description: */
#define APB_CTRL_PERI_BACKUP_ENA (BIT(31))
#define APB_CTRL_PERI_BACKUP_ENA_M (BIT(31))
#define APB_CTRL_PERI_BACKUP_ENA_V 0x1
#define APB_CTRL_PERI_BACKUP_ENA_S 31
/* APB_CTRL_PERI_BACKUP_TO_MEM : R/W ;bitpos:[30] ;default: 1'b0 ; */
/*description: */
#define APB_CTRL_PERI_BACKUP_TO_MEM (BIT(30))
#define APB_CTRL_PERI_BACKUP_TO_MEM_M (BIT(30))
#define APB_CTRL_PERI_BACKUP_TO_MEM_V 0x1
#define APB_CTRL_PERI_BACKUP_TO_MEM_S 30
/* APB_CTRL_PERI_BACKUP_START : WO ;bitpos:[29] ;default: 1'b0 ; */
/*description: */
#define APB_CTRL_PERI_BACKUP_START (BIT(29))
#define APB_CTRL_PERI_BACKUP_START_M (BIT(29))
#define APB_CTRL_PERI_BACKUP_START_V 0x1
#define APB_CTRL_PERI_BACKUP_START_S 29
/* APB_CTRL_PERI_BACKUP_SIZE : R/W ;bitpos:[28:19] ;default: 10'd0 ; */
/*description: */
#define APB_CTRL_PERI_BACKUP_SIZE 0x000003FF
#define APB_CTRL_PERI_BACKUP_SIZE_M ((APB_CTRL_PERI_BACKUP_SIZE_V)<<(APB_CTRL_PERI_BACKUP_SIZE_S))
#define APB_CTRL_PERI_BACKUP_SIZE_V 0x3FF
#define APB_CTRL_PERI_BACKUP_SIZE_S 19
/* APB_CTRL_PERI_BACKUP_TOUT_THRES : R/W ;bitpos:[18:9] ;default: 10'd50 ; */
/*description: */
#define APB_CTRL_PERI_BACKUP_TOUT_THRES 0x000003FF
#define APB_CTRL_PERI_BACKUP_TOUT_THRES_M ((APB_CTRL_PERI_BACKUP_TOUT_THRES_V)<<(APB_CTRL_PERI_BACKUP_TOUT_THRES_S))
#define APB_CTRL_PERI_BACKUP_TOUT_THRES_V 0x3FF
#define APB_CTRL_PERI_BACKUP_TOUT_THRES_S 9
/* APB_CTRL_PERI_BACKUP_BURST_LIMIT : R/W ;bitpos:[8:4] ;default: 5'd8 ; */
/*description: */
#define APB_CTRL_PERI_BACKUP_BURST_LIMIT 0x0000001F
#define APB_CTRL_PERI_BACKUP_BURST_LIMIT_M ((APB_CTRL_PERI_BACKUP_BURST_LIMIT_V)<<(APB_CTRL_PERI_BACKUP_BURST_LIMIT_S))
#define APB_CTRL_PERI_BACKUP_BURST_LIMIT_V 0x1F
#define APB_CTRL_PERI_BACKUP_BURST_LIMIT_S 4
/* APB_CTRL_PERI_BACKUP_FLOW_ERR : RO ;bitpos:[2:1] ;default: 2'd0 ; */
/*description: */
#define APB_CTRL_PERI_BACKUP_FLOW_ERR 0x00000003
#define APB_CTRL_PERI_BACKUP_FLOW_ERR_M ((APB_CTRL_PERI_BACKUP_FLOW_ERR_V)<<(APB_CTRL_PERI_BACKUP_FLOW_ERR_S))
#define APB_CTRL_PERI_BACKUP_FLOW_ERR_V 0x3
#define APB_CTRL_PERI_BACKUP_FLOW_ERR_S 1
#define APB_CTRL_PERI_BACKUP_APB_ADDR_REG (DR_REG_APB_CTRL_BASE + 0x0B8)
/* APB_CTRL_BACKUP_APB_START_ADDR : R/W ;bitpos:[31:0] ;default: 32'd0 ; */
/*description: */
#define APB_CTRL_BACKUP_APB_START_ADDR 0xFFFFFFFF
#define APB_CTRL_BACKUP_APB_START_ADDR_M ((APB_CTRL_BACKUP_APB_START_ADDR_V)<<(APB_CTRL_BACKUP_APB_START_ADDR_S))
#define APB_CTRL_BACKUP_APB_START_ADDR_V 0xFFFFFFFF
#define APB_CTRL_BACKUP_APB_START_ADDR_S 0
#define APB_CTRL_PERI_BACKUP_MEM_ADDR_REG (DR_REG_APB_CTRL_BASE + 0x0BC)
/* APB_CTRL_BACKUP_MEM_START_ADDR : R/W ;bitpos:[31:0] ;default: 32'd0 ; */
/*description: */
#define APB_CTRL_BACKUP_MEM_START_ADDR 0xFFFFFFFF
#define APB_CTRL_BACKUP_MEM_START_ADDR_M ((APB_CTRL_BACKUP_MEM_START_ADDR_V)<<(APB_CTRL_BACKUP_MEM_START_ADDR_S))
#define APB_CTRL_BACKUP_MEM_START_ADDR_V 0xFFFFFFFF
#define APB_CTRL_BACKUP_MEM_START_ADDR_S 0
#define APB_CTRL_PERI_BACKUP_INT_RAW_REG (DR_REG_APB_CTRL_BASE + 0x0C0)
/* APB_CTRL_PERI_BACKUP_ERR_INT_RAW : RO ;bitpos:[1] ;default: 1'd0 ; */
/*description: */
#define APB_CTRL_PERI_BACKUP_ERR_INT_RAW (BIT(1))
#define APB_CTRL_PERI_BACKUP_ERR_INT_RAW_M (BIT(1))
#define APB_CTRL_PERI_BACKUP_ERR_INT_RAW_V 0x1
#define APB_CTRL_PERI_BACKUP_ERR_INT_RAW_S 1
/* APB_CTRL_PERI_BACKUP_DONE_INT_RAW : RO ;bitpos:[0] ;default: 1'd0 ; */
/*description: */
#define APB_CTRL_PERI_BACKUP_DONE_INT_RAW (BIT(0))
#define APB_CTRL_PERI_BACKUP_DONE_INT_RAW_M (BIT(0))
#define APB_CTRL_PERI_BACKUP_DONE_INT_RAW_V 0x1
#define APB_CTRL_PERI_BACKUP_DONE_INT_RAW_S 0
#define APB_CTRL_PERI_BACKUP_INT_ST_REG (DR_REG_APB_CTRL_BASE + 0x0C4)
/* APB_CTRL_PERI_BACKUP_ERR_INT_ST : RO ;bitpos:[1] ;default: 1'd0 ; */
/*description: */
#define APB_CTRL_PERI_BACKUP_ERR_INT_ST (BIT(1))
#define APB_CTRL_PERI_BACKUP_ERR_INT_ST_M (BIT(1))
#define APB_CTRL_PERI_BACKUP_ERR_INT_ST_V 0x1
#define APB_CTRL_PERI_BACKUP_ERR_INT_ST_S 1
/* APB_CTRL_PERI_BACKUP_DONE_INT_ST : RO ;bitpos:[0] ;default: 1'd0 ; */
/*description: */
#define APB_CTRL_PERI_BACKUP_DONE_INT_ST (BIT(0))
#define APB_CTRL_PERI_BACKUP_DONE_INT_ST_M (BIT(0))
#define APB_CTRL_PERI_BACKUP_DONE_INT_ST_V 0x1
#define APB_CTRL_PERI_BACKUP_DONE_INT_ST_S 0
#define APB_CTRL_PERI_BACKUP_INT_ENA_REG (DR_REG_APB_CTRL_BASE + 0x0C8)
/* APB_CTRL_PERI_BACKUP_ERR_INT_ENA : R/W ;bitpos:[1] ;default: 1'd0 ; */
/*description: */
#define APB_CTRL_PERI_BACKUP_ERR_INT_ENA (BIT(1))
#define APB_CTRL_PERI_BACKUP_ERR_INT_ENA_M (BIT(1))
#define APB_CTRL_PERI_BACKUP_ERR_INT_ENA_V 0x1
#define APB_CTRL_PERI_BACKUP_ERR_INT_ENA_S 1
/* APB_CTRL_PERI_BACKUP_DONE_INT_ENA : R/W ;bitpos:[0] ;default: 1'd0 ; */
/*description: */
#define APB_CTRL_PERI_BACKUP_DONE_INT_ENA (BIT(0))
#define APB_CTRL_PERI_BACKUP_DONE_INT_ENA_M (BIT(0))
#define APB_CTRL_PERI_BACKUP_DONE_INT_ENA_V 0x1
#define APB_CTRL_PERI_BACKUP_DONE_INT_ENA_S 0
#define APB_CTRL_PERI_BACKUP_INT_CLR_REG (DR_REG_APB_CTRL_BASE + 0x0D0)
/* APB_CTRL_PERI_BACKUP_ERR_INT_CLR : WO ;bitpos:[1] ;default: 1'd0 ; */
/*description: */
#define APB_CTRL_PERI_BACKUP_ERR_INT_CLR (BIT(1))
#define APB_CTRL_PERI_BACKUP_ERR_INT_CLR_M (BIT(1))
#define APB_CTRL_PERI_BACKUP_ERR_INT_CLR_V 0x1
#define APB_CTRL_PERI_BACKUP_ERR_INT_CLR_S 1
/* APB_CTRL_PERI_BACKUP_DONE_INT_CLR : WO ;bitpos:[0] ;default: 1'd0 ; */
/*description: */
#define APB_CTRL_PERI_BACKUP_DONE_INT_CLR (BIT(0))
#define APB_CTRL_PERI_BACKUP_DONE_INT_CLR_M (BIT(0))
#define APB_CTRL_PERI_BACKUP_DONE_INT_CLR_V 0x1
#define APB_CTRL_PERI_BACKUP_DONE_INT_CLR_S 0
#define APB_CTRL_DATE_REG (DR_REG_APB_CTRL_BASE + 0x3FC)
/* APB_CTRL_DATE : R/W ;bitpos:[31:0] ;default: 32'h2007210 ; */
/*description: Version control*/
#define APB_CTRL_DATE 0xFFFFFFFF
#define APB_CTRL_DATE_M ((APB_CTRL_DATE_V)<<(APB_CTRL_DATE_S))
#define APB_CTRL_DATE_V 0xFFFFFFFF
#define APB_CTRL_DATE_S 0
#ifdef __cplusplus
}
#endif
#endif /*_SOC_APB_CTRL_REG_H_ */

View File

@ -0,0 +1,482 @@
// 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.
#ifndef _SOC_APB_CTRL_STRUCT_H_
#define _SOC_APB_CTRL_STRUCT_H_
#ifdef __cplusplus
extern "C" {
#endif
typedef volatile struct {
union {
struct {
uint32_t pre_div: 10;
uint32_t clk_320m_en: 1;
uint32_t clk_en: 1;
uint32_t rst_tick: 1;
uint32_t reserved13: 19;
};
uint32_t val;
} clk_conf;
union {
struct {
uint32_t xtal_tick: 8;
uint32_t ck8m_tick: 8;
uint32_t tick_enable: 1;
uint32_t reserved17: 15;
};
uint32_t val;
} tick_conf;
union {
struct {
uint32_t clk20_oen: 1;
uint32_t clk22_oen: 1;
uint32_t clk44_oen: 1;
uint32_t clk_bb_oen: 1;
uint32_t clk80_oen: 1;
uint32_t clk160_oen: 1;
uint32_t clk_320m_oen: 1;
uint32_t clk_adc_inf_oen: 1;
uint32_t clk_dac_cpu_oen: 1;
uint32_t clk40x_bb_oen: 1;
uint32_t clk_xtal_oen: 1;
uint32_t reserved11: 21;
};
uint32_t val;
} clk_out_en;
uint32_t wifi_bb_cfg; /**/
uint32_t wifi_bb_cfg_2; /**/
uint32_t wifi_clk_en; /**/
uint32_t wifi_rst_en; /**/
union {
struct {
uint32_t peri_io_swap: 8;
uint32_t reserved8: 24;
};
uint32_t val;
} host_inf_sel;
union {
struct {
uint32_t ext_mem_pms_lock: 1;
uint32_t reserved1: 31;
};
uint32_t val;
} ext_mem_pms_lock;
uint32_t reserved_24;
union {
struct {
uint32_t flash_ace0_attr: 2;
uint32_t reserved2: 30;
};
uint32_t val;
} flash_ace0_attr;
union {
struct {
uint32_t flash_ace1_attr: 2;
uint32_t reserved2: 30;
};
uint32_t val;
} flash_ace1_attr;
union {
struct {
uint32_t flash_ace2_attr: 2;
uint32_t reserved2: 30;
};
uint32_t val;
} flash_ace2_attr;
union {
struct {
uint32_t flash_ace3_attr: 2;
uint32_t reserved2: 30;
};
uint32_t val;
} flash_ace3_attr;
uint32_t flash_ace0_addr; /**/
uint32_t flash_ace1_addr; /**/
uint32_t flash_ace2_addr; /**/
uint32_t flash_ace3_addr; /**/
union {
struct {
uint32_t flash_ace0_size:13;
uint32_t reserved13: 19;
};
uint32_t val;
} flash_ace0_size;
union {
struct {
uint32_t flash_ace1_size:13;
uint32_t reserved13: 19;
};
uint32_t val;
} flash_ace1_size;
union {
struct {
uint32_t flash_ace2_size:13;
uint32_t reserved13: 19;
};
uint32_t val;
} flash_ace2_size;
union {
struct {
uint32_t flash_ace3_size:13;
uint32_t reserved13: 19;
};
uint32_t val;
} flash_ace3_size;
uint32_t reserved_58;
uint32_t reserved_5c;
uint32_t reserved_60;
uint32_t reserved_64;
uint32_t reserved_68;
uint32_t reserved_6c;
uint32_t reserved_70;
uint32_t reserved_74;
uint32_t reserved_78;
uint32_t reserved_7c;
uint32_t reserved_80;
uint32_t reserved_84;
union {
struct {
uint32_t spi_mem_reject_int: 1;
uint32_t spi_mem_reject_clr: 1;
uint32_t spi_mem_reject_cde: 5;
uint32_t reserved7: 25;
};
uint32_t val;
} spi_mem_pms_ctrl;
uint32_t spi_mem_reject_addr; /**/
union {
struct {
uint32_t sdio_win_access_en: 1;
uint32_t reserved1: 31;
};
uint32_t val;
} sdio_ctrl;
union {
struct {
uint32_t redcy_sig0: 31;
uint32_t redcy_andor: 1;
};
uint32_t val;
} redcy_sig0;
union {
struct {
uint32_t redcy_sig1: 31;
uint32_t redcy_nandor: 1;
};
uint32_t val;
} redcy_sig1;
union {
struct {
uint32_t agc_mem_force_pu: 1;
uint32_t agc_mem_force_pd: 1;
uint32_t pbus_mem_force_pu: 1;
uint32_t pbus_mem_force_pd: 1;
uint32_t dc_mem_force_pu: 1;
uint32_t dc_mem_force_pd: 1;
uint32_t reserved6: 26;
};
uint32_t val;
} front_end_mem_pd;
union {
struct {
uint32_t retention_link_addr: 27;
uint32_t nobypass_cpu_iso_rst: 1;
uint32_t reserved28: 4;
};
uint32_t val;
} retention_ctrl;
union {
struct {
uint32_t rom_clkgate_force_on: 2;
uint32_t sram_clkgate_force_on: 4;
uint32_t reserved6: 26;
};
uint32_t val;
} clkgate_force_on;
union {
struct {
uint32_t rom_power_down: 2;
uint32_t sram_power_down: 4;
uint32_t reserved6: 26;
};
uint32_t val;
} mem_power_down;
union {
struct {
uint32_t rom_power_up: 2;
uint32_t sram_power_up: 4;
uint32_t reserved6: 26;
};
uint32_t val;
} mem_power_up;
uint32_t rnd_data; /**/
union {
struct {
uint32_t reserved0: 1;
uint32_t peri_backup_flow_err: 2;
uint32_t reserved3: 1;
uint32_t peri_backup_burst_limit: 5;
uint32_t peri_backup_tout_thres: 10;
uint32_t peri_backup_size: 10;
uint32_t peri_backup_start: 1;
uint32_t peri_backup_to_mem: 1;
uint32_t peri_backup_ena: 1;
};
uint32_t val;
} peri_backup_config;
uint32_t peri_backup_addr; /**/
uint32_t peri_backup_mem_addr; /**/
union {
struct {
uint32_t peri_backup_done: 1;
uint32_t peri_backup_err: 1;
uint32_t reserved2: 30;
};
uint32_t val;
} peri_backup_int_raw;
union {
struct {
uint32_t peri_backup_done: 1;
uint32_t peri_backup_err: 1;
uint32_t reserved2: 30;
};
uint32_t val;
} peri_backup_int_st;
union {
struct {
uint32_t peri_backup_done: 1;
uint32_t peri_backup_err: 1;
uint32_t reserved2: 30;
};
uint32_t val;
} peri_backup_int_ena;
uint32_t reserved_cc;
union {
struct {
uint32_t peri_backup_done: 1;
uint32_t peri_backup_err: 1;
uint32_t reserved2: 30;
};
uint32_t val;
} peri_backup_int_clr;
uint32_t reserved_d4;
uint32_t reserved_d8;
uint32_t reserved_dc;
uint32_t reserved_e0;
uint32_t reserved_e4;
uint32_t reserved_e8;
uint32_t reserved_ec;
uint32_t reserved_f0;
uint32_t reserved_f4;
uint32_t reserved_f8;
uint32_t reserved_fc;
uint32_t reserved_100;
uint32_t reserved_104;
uint32_t reserved_108;
uint32_t reserved_10c;
uint32_t reserved_110;
uint32_t reserved_114;
uint32_t reserved_118;
uint32_t reserved_11c;
uint32_t reserved_120;
uint32_t reserved_124;
uint32_t reserved_128;
uint32_t reserved_12c;
uint32_t reserved_130;
uint32_t reserved_134;
uint32_t reserved_138;
uint32_t reserved_13c;
uint32_t reserved_140;
uint32_t reserved_144;
uint32_t reserved_148;
uint32_t reserved_14c;
uint32_t reserved_150;
uint32_t reserved_154;
uint32_t reserved_158;
uint32_t reserved_15c;
uint32_t reserved_160;
uint32_t reserved_164;
uint32_t reserved_168;
uint32_t reserved_16c;
uint32_t reserved_170;
uint32_t reserved_174;
uint32_t reserved_178;
uint32_t reserved_17c;
uint32_t reserved_180;
uint32_t reserved_184;
uint32_t reserved_188;
uint32_t reserved_18c;
uint32_t reserved_190;
uint32_t reserved_194;
uint32_t reserved_198;
uint32_t reserved_19c;
uint32_t reserved_1a0;
uint32_t reserved_1a4;
uint32_t reserved_1a8;
uint32_t reserved_1ac;
uint32_t reserved_1b0;
uint32_t reserved_1b4;
uint32_t reserved_1b8;
uint32_t reserved_1bc;
uint32_t reserved_1c0;
uint32_t reserved_1c4;
uint32_t reserved_1c8;
uint32_t reserved_1cc;
uint32_t reserved_1d0;
uint32_t reserved_1d4;
uint32_t reserved_1d8;
uint32_t reserved_1dc;
uint32_t reserved_1e0;
uint32_t reserved_1e4;
uint32_t reserved_1e8;
uint32_t reserved_1ec;
uint32_t reserved_1f0;
uint32_t reserved_1f4;
uint32_t reserved_1f8;
uint32_t reserved_1fc;
uint32_t reserved_200;
uint32_t reserved_204;
uint32_t reserved_208;
uint32_t reserved_20c;
uint32_t reserved_210;
uint32_t reserved_214;
uint32_t reserved_218;
uint32_t reserved_21c;
uint32_t reserved_220;
uint32_t reserved_224;
uint32_t reserved_228;
uint32_t reserved_22c;
uint32_t reserved_230;
uint32_t reserved_234;
uint32_t reserved_238;
uint32_t reserved_23c;
uint32_t reserved_240;
uint32_t reserved_244;
uint32_t reserved_248;
uint32_t reserved_24c;
uint32_t reserved_250;
uint32_t reserved_254;
uint32_t reserved_258;
uint32_t reserved_25c;
uint32_t reserved_260;
uint32_t reserved_264;
uint32_t reserved_268;
uint32_t reserved_26c;
uint32_t reserved_270;
uint32_t reserved_274;
uint32_t reserved_278;
uint32_t reserved_27c;
uint32_t reserved_280;
uint32_t reserved_284;
uint32_t reserved_288;
uint32_t reserved_28c;
uint32_t reserved_290;
uint32_t reserved_294;
uint32_t reserved_298;
uint32_t reserved_29c;
uint32_t reserved_2a0;
uint32_t reserved_2a4;
uint32_t reserved_2a8;
uint32_t reserved_2ac;
uint32_t reserved_2b0;
uint32_t reserved_2b4;
uint32_t reserved_2b8;
uint32_t reserved_2bc;
uint32_t reserved_2c0;
uint32_t reserved_2c4;
uint32_t reserved_2c8;
uint32_t reserved_2cc;
uint32_t reserved_2d0;
uint32_t reserved_2d4;
uint32_t reserved_2d8;
uint32_t reserved_2dc;
uint32_t reserved_2e0;
uint32_t reserved_2e4;
uint32_t reserved_2e8;
uint32_t reserved_2ec;
uint32_t reserved_2f0;
uint32_t reserved_2f4;
uint32_t reserved_2f8;
uint32_t reserved_2fc;
uint32_t reserved_300;
uint32_t reserved_304;
uint32_t reserved_308;
uint32_t reserved_30c;
uint32_t reserved_310;
uint32_t reserved_314;
uint32_t reserved_318;
uint32_t reserved_31c;
uint32_t reserved_320;
uint32_t reserved_324;
uint32_t reserved_328;
uint32_t reserved_32c;
uint32_t reserved_330;
uint32_t reserved_334;
uint32_t reserved_338;
uint32_t reserved_33c;
uint32_t reserved_340;
uint32_t reserved_344;
uint32_t reserved_348;
uint32_t reserved_34c;
uint32_t reserved_350;
uint32_t reserved_354;
uint32_t reserved_358;
uint32_t reserved_35c;
uint32_t reserved_360;
uint32_t reserved_364;
uint32_t reserved_368;
uint32_t reserved_36c;
uint32_t reserved_370;
uint32_t reserved_374;
uint32_t reserved_378;
uint32_t reserved_37c;
uint32_t reserved_380;
uint32_t reserved_384;
uint32_t reserved_388;
uint32_t reserved_38c;
uint32_t reserved_390;
uint32_t reserved_394;
uint32_t reserved_398;
uint32_t reserved_39c;
uint32_t reserved_3a0;
uint32_t reserved_3a4;
uint32_t reserved_3a8;
uint32_t reserved_3ac;
uint32_t reserved_3b0;
uint32_t reserved_3b4;
uint32_t reserved_3b8;
uint32_t reserved_3bc;
uint32_t reserved_3c0;
uint32_t reserved_3c4;
uint32_t reserved_3c8;
uint32_t reserved_3cc;
uint32_t reserved_3d0;
uint32_t reserved_3d4;
uint32_t reserved_3d8;
uint32_t reserved_3dc;
uint32_t reserved_3e0;
uint32_t reserved_3e4;
uint32_t reserved_3e8;
uint32_t reserved_3ec;
uint32_t reserved_3f0;
uint32_t reserved_3f4;
uint32_t reserved_3f8;
uint32_t date; /*Version control*/
} apb_ctrl_dev_t;
extern apb_ctrl_dev_t APB_CTRL;
#ifdef __cplusplus
}
#endif
#endif /* _SOC_APB_CTRL_STRUCT_H_ */

View File

@ -0,0 +1,631 @@
// 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.
#ifndef _SOC_APB_SARADC_REG_H_
#define _SOC_APB_SARADC_REG_H_
#ifdef __cplusplus
extern "C" {
#endif
#include "soc.h"
#define APB_SARADC_CTRL_REG (DR_REG_APB_SARADC_BASE + 0x000)
/* APB_SARADC_WAIT_ARB_CYCLE : R/W ;bitpos:[31:30] ;default: 2'd1 ; */
/*description: wait arbit signal stable after sar_done*/
#define APB_SARADC_WAIT_ARB_CYCLE 0x00000003
#define APB_SARADC_WAIT_ARB_CYCLE_M ((APB_SARADC_WAIT_ARB_CYCLE_V)<<(APB_SARADC_WAIT_ARB_CYCLE_S))
#define APB_SARADC_WAIT_ARB_CYCLE_V 0x3
#define APB_SARADC_WAIT_ARB_CYCLE_S 30
/* APB_SARADC_XPD_SAR_FORCE : R/W ;bitpos:[28:27] ;default: 2'd0 ; */
/*description: force option to xpd sar blocks*/
#define APB_SARADC_XPD_SAR_FORCE 0x00000003
#define APB_SARADC_XPD_SAR_FORCE_M ((APB_SARADC_XPD_SAR_FORCE_V)<<(APB_SARADC_XPD_SAR_FORCE_S))
#define APB_SARADC_XPD_SAR_FORCE_V 0x3
#define APB_SARADC_XPD_SAR_FORCE_S 27
/* APB_SARADC_SAR_PATT_P_CLEAR : R/W ;bitpos:[23] ;default: 1'd0 ; */
/*description: clear the pointer of pattern table for DIG ADC1 CTRL*/
#define APB_SARADC_SAR_PATT_P_CLEAR (BIT(23))
#define APB_SARADC_SAR_PATT_P_CLEAR_M (BIT(23))
#define APB_SARADC_SAR_PATT_P_CLEAR_V 0x1
#define APB_SARADC_SAR_PATT_P_CLEAR_S 23
/* APB_SARADC_SAR_PATT_LEN : R/W ;bitpos:[17:15] ;default: 3'd7 ; */
/*description: 0 ~ 15 means length 1 ~ 16*/
#define APB_SARADC_SAR_PATT_LEN 0x00000007
#define APB_SARADC_SAR_PATT_LEN_M ((APB_SARADC_SAR_PATT_LEN_V)<<(APB_SARADC_SAR_PATT_LEN_S))
#define APB_SARADC_SAR_PATT_LEN_V 0x7
#define APB_SARADC_SAR_PATT_LEN_S 15
/* APB_SARADC_SAR_CLK_DIV : R/W ;bitpos:[14:7] ;default: 8'd4 ; */
/*description: SAR clock divider*/
#define APB_SARADC_SAR_CLK_DIV 0x000000FF
#define APB_SARADC_SAR_CLK_DIV_M ((APB_SARADC_SAR_CLK_DIV_V)<<(APB_SARADC_SAR_CLK_DIV_S))
#define APB_SARADC_SAR_CLK_DIV_V 0xFF
#define APB_SARADC_SAR_CLK_DIV_S 7
/* APB_SARADC_SAR_CLK_GATED : R/W ;bitpos:[6] ;default: 1'b1 ; */
/*description: */
#define APB_SARADC_SAR_CLK_GATED (BIT(6))
#define APB_SARADC_SAR_CLK_GATED_M (BIT(6))
#define APB_SARADC_SAR_CLK_GATED_V 0x1
#define APB_SARADC_SAR_CLK_GATED_S 6
/* APB_SARADC_START : R/W ;bitpos:[1] ;default: 1'd0 ; */
/*description: */
#define APB_SARADC_START (BIT(1))
#define APB_SARADC_START_M (BIT(1))
#define APB_SARADC_START_V 0x1
#define APB_SARADC_START_S 1
/* APB_SARADC_START_FORCE : R/W ;bitpos:[0] ;default: 1'd0 ; */
/*description: */
#define APB_SARADC_START_FORCE (BIT(0))
#define APB_SARADC_START_FORCE_M (BIT(0))
#define APB_SARADC_START_FORCE_V 0x1
#define APB_SARADC_START_FORCE_S 0
#define APB_SARADC_CTRL2_REG (DR_REG_APB_SARADC_BASE + 0x004)
/* APB_SARADC_TIMER_EN : R/W ;bitpos:[24] ;default: 1'd0 ; */
/*description: to enable saradc timer trigger*/
#define APB_SARADC_TIMER_EN (BIT(24))
#define APB_SARADC_TIMER_EN_M (BIT(24))
#define APB_SARADC_TIMER_EN_V 0x1
#define APB_SARADC_TIMER_EN_S 24
/* APB_SARADC_TIMER_TARGET : R/W ;bitpos:[23:12] ;default: 12'd10 ; */
/*description: to set saradc timer target*/
#define APB_SARADC_TIMER_TARGET 0x00000FFF
#define APB_SARADC_TIMER_TARGET_M ((APB_SARADC_TIMER_TARGET_V)<<(APB_SARADC_TIMER_TARGET_S))
#define APB_SARADC_TIMER_TARGET_V 0xFFF
#define APB_SARADC_TIMER_TARGET_S 12
/* APB_SARADC_SAR2_INV : R/W ;bitpos:[10] ;default: 1'd0 ; */
/*description: 1: data to DIG ADC2 CTRL is inverted otherwise not*/
#define APB_SARADC_SAR2_INV (BIT(10))
#define APB_SARADC_SAR2_INV_M (BIT(10))
#define APB_SARADC_SAR2_INV_V 0x1
#define APB_SARADC_SAR2_INV_S 10
/* APB_SARADC_SAR1_INV : R/W ;bitpos:[9] ;default: 1'd0 ; */
/*description: 1: data to DIG ADC1 CTRL is inverted otherwise not*/
#define APB_SARADC_SAR1_INV (BIT(9))
#define APB_SARADC_SAR1_INV_M (BIT(9))
#define APB_SARADC_SAR1_INV_V 0x1
#define APB_SARADC_SAR1_INV_S 9
/* APB_SARADC_MAX_MEAS_NUM : R/W ;bitpos:[8:1] ;default: 8'd255 ; */
/*description: max conversion number*/
#define APB_SARADC_MAX_MEAS_NUM 0x000000FF
#define APB_SARADC_MAX_MEAS_NUM_M ((APB_SARADC_MAX_MEAS_NUM_V)<<(APB_SARADC_MAX_MEAS_NUM_S))
#define APB_SARADC_MAX_MEAS_NUM_V 0xFF
#define APB_SARADC_MAX_MEAS_NUM_S 1
/* APB_SARADC_MEAS_NUM_LIMIT : R/W ;bitpos:[0] ;default: 1'd0 ; */
/*description: */
#define APB_SARADC_MEAS_NUM_LIMIT (BIT(0))
#define APB_SARADC_MEAS_NUM_LIMIT_M (BIT(0))
#define APB_SARADC_MEAS_NUM_LIMIT_V 0x1
#define APB_SARADC_MEAS_NUM_LIMIT_S 0
#define APB_SARADC_FILTER_CTRL1_REG (DR_REG_APB_SARADC_BASE + 0x008)
/* APB_SARADC_FILTER_FACTOR0 : R/W ;bitpos:[31:29] ;default: 3'd0 ; */
/*description: */
#define APB_SARADC_FILTER_FACTOR0 0x00000007
#define APB_SARADC_FILTER_FACTOR0_M ((APB_SARADC_FILTER_FACTOR0_V)<<(APB_SARADC_FILTER_FACTOR0_S))
#define APB_SARADC_FILTER_FACTOR0_V 0x7
#define APB_SARADC_FILTER_FACTOR0_S 29
/* APB_SARADC_FILTER_FACTOR1 : R/W ;bitpos:[28:26] ;default: 3'd0 ; */
/*description: */
#define APB_SARADC_FILTER_FACTOR1 0x00000007
#define APB_SARADC_FILTER_FACTOR1_M ((APB_SARADC_FILTER_FACTOR1_V)<<(APB_SARADC_FILTER_FACTOR1_S))
#define APB_SARADC_FILTER_FACTOR1_V 0x7
#define APB_SARADC_FILTER_FACTOR1_S 26
#define APB_SARADC_FSM_WAIT_REG (DR_REG_APB_SARADC_BASE + 0x00C)
/* APB_SARADC_STANDBY_WAIT : R/W ;bitpos:[23:16] ;default: 8'd255 ; */
/*description: */
#define APB_SARADC_STANDBY_WAIT 0x000000FF
#define APB_SARADC_STANDBY_WAIT_M ((APB_SARADC_STANDBY_WAIT_V)<<(APB_SARADC_STANDBY_WAIT_S))
#define APB_SARADC_STANDBY_WAIT_V 0xFF
#define APB_SARADC_STANDBY_WAIT_S 16
/* APB_SARADC_RSTB_WAIT : R/W ;bitpos:[15:8] ;default: 8'd8 ; */
/*description: */
#define APB_SARADC_RSTB_WAIT 0x000000FF
#define APB_SARADC_RSTB_WAIT_M ((APB_SARADC_RSTB_WAIT_V)<<(APB_SARADC_RSTB_WAIT_S))
#define APB_SARADC_RSTB_WAIT_V 0xFF
#define APB_SARADC_RSTB_WAIT_S 8
/* APB_SARADC_XPD_WAIT : R/W ;bitpos:[7:0] ;default: 8'd8 ; */
/*description: */
#define APB_SARADC_XPD_WAIT 0x000000FF
#define APB_SARADC_XPD_WAIT_M ((APB_SARADC_XPD_WAIT_V)<<(APB_SARADC_XPD_WAIT_S))
#define APB_SARADC_XPD_WAIT_V 0xFF
#define APB_SARADC_XPD_WAIT_S 0
#define APB_SARADC_SAR1_STATUS_REG (DR_REG_APB_SARADC_BASE + 0x010)
/* APB_SARADC_SAR1_STATUS : RO ;bitpos:[31:0] ;default: 32'd0 ; */
/*description: */
#define APB_SARADC_SAR1_STATUS 0xFFFFFFFF
#define APB_SARADC_SAR1_STATUS_M ((APB_SARADC_SAR1_STATUS_V)<<(APB_SARADC_SAR1_STATUS_S))
#define APB_SARADC_SAR1_STATUS_V 0xFFFFFFFF
#define APB_SARADC_SAR1_STATUS_S 0
#define APB_SARADC_SAR2_STATUS_REG (DR_REG_APB_SARADC_BASE + 0x014)
/* APB_SARADC_SAR2_STATUS : RO ;bitpos:[31:0] ;default: 32'd0 ; */
/*description: */
#define APB_SARADC_SAR2_STATUS 0xFFFFFFFF
#define APB_SARADC_SAR2_STATUS_M ((APB_SARADC_SAR2_STATUS_V)<<(APB_SARADC_SAR2_STATUS_S))
#define APB_SARADC_SAR2_STATUS_V 0xFFFFFFFF
#define APB_SARADC_SAR2_STATUS_S 0
#define APB_SARADC_SAR_PATT_TAB1_REG (DR_REG_APB_SARADC_BASE + 0x018)
/* APB_SARADC_SAR_PATT_TAB1 : R/W ;bitpos:[23:0] ;default: 24'h0 ; */
/*description: item 0 ~ 3 for pattern table 1 (each item one byte)*/
#define APB_SARADC_SAR_PATT_TAB1 0x00FFFFFF
#define APB_SARADC_SAR_PATT_TAB1_M ((APB_SARADC_SAR_PATT_TAB1_V)<<(APB_SARADC_SAR_PATT_TAB1_S))
#define APB_SARADC_SAR_PATT_TAB1_V 0xFFFFFF
#define APB_SARADC_SAR_PATT_TAB1_S 0
#define APB_SARADC_SAR_PATT_TAB2_REG (DR_REG_APB_SARADC_BASE + 0x01C)
/* APB_SARADC_SAR_PATT_TAB2 : R/W ;bitpos:[23:0] ;default: 24'h0 ; */
/*description: Item 4 ~ 7 for pattern table 1 (each item one byte)*/
#define APB_SARADC_SAR_PATT_TAB2 0x00FFFFFF
#define APB_SARADC_SAR_PATT_TAB2_M ((APB_SARADC_SAR_PATT_TAB2_V)<<(APB_SARADC_SAR_PATT_TAB2_S))
#define APB_SARADC_SAR_PATT_TAB2_V 0xFFFFFF
#define APB_SARADC_SAR_PATT_TAB2_S 0
#define APB_SARADC_ONETIME_SAMPLE_REG (DR_REG_APB_SARADC_BASE + 0x020)
/* APB_SARADC1_ONETIME_SAMPLE : R/W ;bitpos:[31] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC1_ONETIME_SAMPLE (BIT(31))
#define APB_SARADC1_ONETIME_SAMPLE_M (BIT(31))
#define APB_SARADC1_ONETIME_SAMPLE_V 0x1
#define APB_SARADC1_ONETIME_SAMPLE_S 31
/* APB_SARADC2_ONETIME_SAMPLE : R/W ;bitpos:[30] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC2_ONETIME_SAMPLE (BIT(30))
#define APB_SARADC2_ONETIME_SAMPLE_M (BIT(30))
#define APB_SARADC2_ONETIME_SAMPLE_V 0x1
#define APB_SARADC2_ONETIME_SAMPLE_S 30
/* APB_SARADC_ONETIME_START : R/W ;bitpos:[29] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_ONETIME_START (BIT(29))
#define APB_SARADC_ONETIME_START_M (BIT(29))
#define APB_SARADC_ONETIME_START_V 0x1
#define APB_SARADC_ONETIME_START_S 29
/* APB_SARADC_ONETIME_CHANNEL : R/W ;bitpos:[28:25] ;default: 4'd13 ; */
/*description: */
#define APB_SARADC_ONETIME_CHANNEL 0x0000000F
#define APB_SARADC_ONETIME_CHANNEL_M ((APB_SARADC_ONETIME_CHANNEL_V)<<(APB_SARADC_ONETIME_CHANNEL_S))
#define APB_SARADC_ONETIME_CHANNEL_V 0xF
#define APB_SARADC_ONETIME_CHANNEL_S 25
/* APB_SARADC_ONETIME_ATTEN : R/W ;bitpos:[24:23] ;default: 2'd0 ; */
/*description: */
#define APB_SARADC_ONETIME_ATTEN 0x00000003
#define APB_SARADC_ONETIME_ATTEN_M ((APB_SARADC_ONETIME_ATTEN_V)<<(APB_SARADC_ONETIME_ATTEN_S))
#define APB_SARADC_ONETIME_ATTEN_V 0x3
#define APB_SARADC_ONETIME_ATTEN_S 23
#define APB_SARADC_APB_ADC_ARB_CTRL_REG (DR_REG_APB_SARADC_BASE + 0x024)
/* APB_SARADC_ADC_ARB_FIX_PRIORITY : R/W ;bitpos:[12] ;default: 1'b0 ; */
/*description: adc2 arbiter uses fixed priority*/
#define APB_SARADC_ADC_ARB_FIX_PRIORITY (BIT(12))
#define APB_SARADC_ADC_ARB_FIX_PRIORITY_M (BIT(12))
#define APB_SARADC_ADC_ARB_FIX_PRIORITY_V 0x1
#define APB_SARADC_ADC_ARB_FIX_PRIORITY_S 12
/* APB_SARADC_ADC_ARB_WIFI_PRIORITY : R/W ;bitpos:[11:10] ;default: 2'd2 ; */
/*description: Set adc2 arbiter wifi priority*/
#define APB_SARADC_ADC_ARB_WIFI_PRIORITY 0x00000003
#define APB_SARADC_ADC_ARB_WIFI_PRIORITY_M ((APB_SARADC_ADC_ARB_WIFI_PRIORITY_V)<<(APB_SARADC_ADC_ARB_WIFI_PRIORITY_S))
#define APB_SARADC_ADC_ARB_WIFI_PRIORITY_V 0x3
#define APB_SARADC_ADC_ARB_WIFI_PRIORITY_S 10
/* APB_SARADC_ADC_ARB_RTC_PRIORITY : R/W ;bitpos:[9:8] ;default: 2'd1 ; */
/*description: Set adc2 arbiter rtc priority*/
#define APB_SARADC_ADC_ARB_RTC_PRIORITY 0x00000003
#define APB_SARADC_ADC_ARB_RTC_PRIORITY_M ((APB_SARADC_ADC_ARB_RTC_PRIORITY_V)<<(APB_SARADC_ADC_ARB_RTC_PRIORITY_S))
#define APB_SARADC_ADC_ARB_RTC_PRIORITY_V 0x3
#define APB_SARADC_ADC_ARB_RTC_PRIORITY_S 8
/* APB_SARADC_ADC_ARB_APB_PRIORITY : R/W ;bitpos:[7:6] ;default: 2'd0 ; */
/*description: Set adc2 arbiterapb priority*/
#define APB_SARADC_ADC_ARB_APB_PRIORITY 0x00000003
#define APB_SARADC_ADC_ARB_APB_PRIORITY_M ((APB_SARADC_ADC_ARB_APB_PRIORITY_V)<<(APB_SARADC_ADC_ARB_APB_PRIORITY_S))
#define APB_SARADC_ADC_ARB_APB_PRIORITY_V 0x3
#define APB_SARADC_ADC_ARB_APB_PRIORITY_S 6
/* APB_SARADC_ADC_ARB_GRANT_FORCE : R/W ;bitpos:[5] ;default: 1'b0 ; */
/*description: adc2 arbiter force grant*/
#define APB_SARADC_ADC_ARB_GRANT_FORCE (BIT(5))
#define APB_SARADC_ADC_ARB_GRANT_FORCE_M (BIT(5))
#define APB_SARADC_ADC_ARB_GRANT_FORCE_V 0x1
#define APB_SARADC_ADC_ARB_GRANT_FORCE_S 5
/* APB_SARADC_ADC_ARB_WIFI_FORCE : R/W ;bitpos:[4] ;default: 1'b0 ; */
/*description: adc2 arbiter force to enable wifi controller*/
#define APB_SARADC_ADC_ARB_WIFI_FORCE (BIT(4))
#define APB_SARADC_ADC_ARB_WIFI_FORCE_M (BIT(4))
#define APB_SARADC_ADC_ARB_WIFI_FORCE_V 0x1
#define APB_SARADC_ADC_ARB_WIFI_FORCE_S 4
/* APB_SARADC_ADC_ARB_RTC_FORCE : R/W ;bitpos:[3] ;default: 1'b0 ; */
/*description: adc2 arbiter force to enable rtc controller*/
#define APB_SARADC_ADC_ARB_RTC_FORCE (BIT(3))
#define APB_SARADC_ADC_ARB_RTC_FORCE_M (BIT(3))
#define APB_SARADC_ADC_ARB_RTC_FORCE_V 0x1
#define APB_SARADC_ADC_ARB_RTC_FORCE_S 3
/* APB_SARADC_ADC_ARB_APB_FORCE : R/W ;bitpos:[2] ;default: 1'b0 ; */
/*description: adc2 arbiter force to enableapb controller*/
#define APB_SARADC_ADC_ARB_APB_FORCE (BIT(2))
#define APB_SARADC_ADC_ARB_APB_FORCE_M (BIT(2))
#define APB_SARADC_ADC_ARB_APB_FORCE_V 0x1
#define APB_SARADC_ADC_ARB_APB_FORCE_S 2
#define APB_SARADC_FILTER_CTRL0_REG (DR_REG_APB_SARADC_BASE + 0x028)
/* APB_SARADC_FILTER_RESET : R/W ;bitpos:[31] ;default: 1'b0 ; */
/*description: enable apb_adc1_filter*/
#define APB_SARADC_FILTER_RESET (BIT(31))
#define APB_SARADC_FILTER_RESET_M (BIT(31))
#define APB_SARADC_FILTER_RESET_V 0x1
#define APB_SARADC_FILTER_RESET_S 31
/* APB_SARADC_FILTER_CHANNEL0 : R/W ;bitpos:[25:22] ;default: 4'd13 ; */
/*description: apb_adc1_filter_factor*/
#define APB_SARADC_FILTER_CHANNEL0 0x0000000F
#define APB_SARADC_FILTER_CHANNEL0_M ((APB_SARADC_FILTER_CHANNEL0_V)<<(APB_SARADC_FILTER_CHANNEL0_S))
#define APB_SARADC_FILTER_CHANNEL0_V 0xF
#define APB_SARADC_FILTER_CHANNEL0_S 22
/* APB_SARADC_FILTER_CHANNEL1 : R/W ;bitpos:[21:18] ;default: 4'd13 ; */
/*description: */
#define APB_SARADC_FILTER_CHANNEL1 0x0000000F
#define APB_SARADC_FILTER_CHANNEL1_M ((APB_SARADC_FILTER_CHANNEL1_V)<<(APB_SARADC_FILTER_CHANNEL1_S))
#define APB_SARADC_FILTER_CHANNEL1_V 0xF
#define APB_SARADC_FILTER_CHANNEL1_S 18
#define APB_SARADC_1_DATA_STATUS_REG (DR_REG_APB_SARADC_BASE + 0x02C)
/* APB_SARADC_ADC1_DATA : RO ;bitpos:[16:0] ;default: 17'd0 ; */
/*description: */
#define APB_SARADC_ADC1_DATA 0x0001FFFF
#define APB_SARADC_ADC1_DATA_M ((APB_SARADC_ADC1_DATA_V)<<(APB_SARADC_ADC1_DATA_S))
#define APB_SARADC_ADC1_DATA_V 0x1FFFF
#define APB_SARADC_ADC1_DATA_S 0
#define APB_SARADC_2_DATA_STATUS_REG (DR_REG_APB_SARADC_BASE + 0x030)
/* APB_SARADC_ADC2_DATA : RO ;bitpos:[16:0] ;default: 17'd0 ; */
/*description: */
#define APB_SARADC_ADC2_DATA 0x0001FFFF
#define APB_SARADC_ADC2_DATA_M ((APB_SARADC_ADC2_DATA_V)<<(APB_SARADC_ADC2_DATA_S))
#define APB_SARADC_ADC2_DATA_V 0x1FFFF
#define APB_SARADC_ADC2_DATA_S 0
#define APB_SARADC_THRES0_CTRL_REG (DR_REG_APB_SARADC_BASE + 0x034)
/* APB_SARADC_THRES0_LOW : R/W ;bitpos:[30:18] ;default: 13'd0 ; */
/*description: saradc1's thres0 monitor thres*/
#define APB_SARADC_THRES0_LOW 0x00001FFF
#define APB_SARADC_THRES0_LOW_M ((APB_SARADC_THRES0_LOW_V)<<(APB_SARADC_THRES0_LOW_S))
#define APB_SARADC_THRES0_LOW_V 0x1FFF
#define APB_SARADC_THRES0_LOW_S 18
/* APB_SARADC_THRES0_HIGH : R/W ;bitpos:[17:5] ;default: 13'h1fff ; */
/*description: saradc1's thres0 monitor thres*/
#define APB_SARADC_THRES0_HIGH 0x00001FFF
#define APB_SARADC_THRES0_HIGH_M ((APB_SARADC_THRES0_HIGH_V)<<(APB_SARADC_THRES0_HIGH_S))
#define APB_SARADC_THRES0_HIGH_V 0x1FFF
#define APB_SARADC_THRES0_HIGH_S 5
/* APB_SARADC_THRES0_CHANNEL : R/W ;bitpos:[3:0] ;default: 4'd13 ; */
/*description: */
#define APB_SARADC_THRES0_CHANNEL 0x0000000F
#define APB_SARADC_THRES0_CHANNEL_M ((APB_SARADC_THRES0_CHANNEL_V)<<(APB_SARADC_THRES0_CHANNEL_S))
#define APB_SARADC_THRES0_CHANNEL_V 0xF
#define APB_SARADC_THRES0_CHANNEL_S 0
#define APB_SARADC_THRES1_CTRL_REG (DR_REG_APB_SARADC_BASE + 0x038)
/* APB_SARADC_THRES1_LOW : R/W ;bitpos:[30:18] ;default: 13'd0 ; */
/*description: saradc1's thres0 monitor thres*/
#define APB_SARADC_THRES1_LOW 0x00001FFF
#define APB_SARADC_THRES1_LOW_M ((APB_SARADC_THRES1_LOW_V)<<(APB_SARADC_THRES1_LOW_S))
#define APB_SARADC_THRES1_LOW_V 0x1FFF
#define APB_SARADC_THRES1_LOW_S 18
/* APB_SARADC_THRES1_HIGH : R/W ;bitpos:[17:5] ;default: 13'h1fff ; */
/*description: saradc1's thres0 monitor thres*/
#define APB_SARADC_THRES1_HIGH 0x00001FFF
#define APB_SARADC_THRES1_HIGH_M ((APB_SARADC_THRES1_HIGH_V)<<(APB_SARADC_THRES1_HIGH_S))
#define APB_SARADC_THRES1_HIGH_V 0x1FFF
#define APB_SARADC_THRES1_HIGH_S 5
/* APB_SARADC_THRES1_CHANNEL : R/W ;bitpos:[3:0] ;default: 4'd13 ; */
/*description: */
#define APB_SARADC_THRES1_CHANNEL 0x0000000F
#define APB_SARADC_THRES1_CHANNEL_M ((APB_SARADC_THRES1_CHANNEL_V)<<(APB_SARADC_THRES1_CHANNEL_S))
#define APB_SARADC_THRES1_CHANNEL_V 0xF
#define APB_SARADC_THRES1_CHANNEL_S 0
#define APB_SARADC_THRES_CTRL_REG (DR_REG_APB_SARADC_BASE + 0x03C)
/* APB_SARADC_THRES0_EN : R/W ;bitpos:[31] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_THRES0_EN (BIT(31))
#define APB_SARADC_THRES0_EN_M (BIT(31))
#define APB_SARADC_THRES0_EN_V 0x1
#define APB_SARADC_THRES0_EN_S 31
/* APB_SARADC_THRES1_EN : R/W ;bitpos:[30] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_THRES1_EN (BIT(30))
#define APB_SARADC_THRES1_EN_M (BIT(30))
#define APB_SARADC_THRES1_EN_V 0x1
#define APB_SARADC_THRES1_EN_S 30
/*description: */
#define APB_SARADC_THRES_ALL_EN (BIT(27))
#define APB_SARADC_THRES_ALL_EN_M (BIT(27))
#define APB_SARADC_THRES_ALL_EN_V 0x1
#define APB_SARADC_THRES_ALL_EN_S 27
#define APB_SARADC_INT_ENA_REG (DR_REG_APB_SARADC_BASE + 0x040)
/* APB_SARADC_ADC1_DONE_INT_ENA : R/W ;bitpos:[31] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_ADC1_DONE_INT_ENA (BIT(31))
#define APB_SARADC_ADC1_DONE_INT_ENA_M (BIT(31))
#define APB_SARADC_ADC1_DONE_INT_ENA_V 0x1
#define APB_SARADC_ADC1_DONE_INT_ENA_S 31
/* APB_SARADC_ADC2_DONE_INT_ENA : R/W ;bitpos:[30] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_ADC2_DONE_INT_ENA (BIT(30))
#define APB_SARADC_ADC2_DONE_INT_ENA_M (BIT(30))
#define APB_SARADC_ADC2_DONE_INT_ENA_V 0x1
#define APB_SARADC_ADC2_DONE_INT_ENA_S 30
/* APB_SARADC_THRES0_HIGH_INT_ENA : R/W ;bitpos:[29] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_THRES0_HIGH_INT_ENA (BIT(29))
#define APB_SARADC_THRES0_HIGH_INT_ENA_M (BIT(29))
#define APB_SARADC_THRES0_HIGH_INT_ENA_V 0x1
#define APB_SARADC_THRES0_HIGH_INT_ENA_S 29
/* APB_SARADC_THRES1_HIGH_INT_ENA : R/W ;bitpos:[28] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_THRES1_HIGH_INT_ENA (BIT(28))
#define APB_SARADC_THRES1_HIGH_INT_ENA_M (BIT(28))
#define APB_SARADC_THRES1_HIGH_INT_ENA_V 0x1
#define APB_SARADC_THRES1_HIGH_INT_ENA_S 28
/* APB_SARADC_THRES0_LOW_INT_ENA : R/W ;bitpos:[27] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_THRES0_LOW_INT_ENA (BIT(27))
#define APB_SARADC_THRES0_LOW_INT_ENA_M (BIT(27))
#define APB_SARADC_THRES0_LOW_INT_ENA_V 0x1
#define APB_SARADC_THRES0_LOW_INT_ENA_S 27
/* APB_SARADC_THRES1_LOW_INT_ENA : R/W ;bitpos:[26] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_THRES1_LOW_INT_ENA (BIT(26))
#define APB_SARADC_THRES1_LOW_INT_ENA_M (BIT(26))
#define APB_SARADC_THRES1_LOW_INT_ENA_V 0x1
#define APB_SARADC_THRES1_LOW_INT_ENA_S 26
#define APB_SARADC_INT_RAW_REG (DR_REG_APB_SARADC_BASE + 0x044)
/* APB_SARADC_ADC1_DONE_INT_RAW : RO ;bitpos:[31] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_ADC1_DONE_INT_RAW (BIT(31))
#define APB_SARADC_ADC1_DONE_INT_RAW_M (BIT(31))
#define APB_SARADC_ADC1_DONE_INT_RAW_V 0x1
#define APB_SARADC_ADC1_DONE_INT_RAW_S 31
/* APB_SARADC_ADC2_DONE_INT_RAW : RO ;bitpos:[30] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_ADC2_DONE_INT_RAW (BIT(30))
#define APB_SARADC_ADC2_DONE_INT_RAW_M (BIT(30))
#define APB_SARADC_ADC2_DONE_INT_RAW_V 0x1
#define APB_SARADC_ADC2_DONE_INT_RAW_S 30
/* APB_SARADC_THRES0_HIGH_INT_RAW : RO ;bitpos:[29] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_THRES0_HIGH_INT_RAW (BIT(29))
#define APB_SARADC_THRES0_HIGH_INT_RAW_M (BIT(29))
#define APB_SARADC_THRES0_HIGH_INT_RAW_V 0x1
#define APB_SARADC_THRES0_HIGH_INT_RAW_S 29
/* APB_SARADC_THRES1_HIGH_INT_RAW : RO ;bitpos:[28] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_THRES1_HIGH_INT_RAW (BIT(28))
#define APB_SARADC_THRES1_HIGH_INT_RAW_M (BIT(28))
#define APB_SARADC_THRES1_HIGH_INT_RAW_V 0x1
#define APB_SARADC_THRES1_HIGH_INT_RAW_S 28
/* APB_SARADC_THRES0_LOW_INT_RAW : RO ;bitpos:[27] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_THRES0_LOW_INT_RAW (BIT(27))
#define APB_SARADC_THRES0_LOW_INT_RAW_M (BIT(27))
#define APB_SARADC_THRES0_LOW_INT_RAW_V 0x1
#define APB_SARADC_THRES0_LOW_INT_RAW_S 27
/* APB_SARADC_THRES1_LOW_INT_RAW : RO ;bitpos:[26] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_THRES1_LOW_INT_RAW (BIT(26))
#define APB_SARADC_THRES1_LOW_INT_RAW_M (BIT(26))
#define APB_SARADC_THRES1_LOW_INT_RAW_V 0x1
#define APB_SARADC_THRES1_LOW_INT_RAW_S 26
#define APB_SARADC_INT_ST_REG (DR_REG_APB_SARADC_BASE + 0x048)
/* APB_SARADC_ADC1_DONE_INT_ST : RO ;bitpos:[31] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_ADC1_DONE_INT_ST (BIT(31))
#define APB_SARADC_ADC1_DONE_INT_ST_M (BIT(31))
#define APB_SARADC_ADC1_DONE_INT_ST_V 0x1
#define APB_SARADC_ADC1_DONE_INT_ST_S 31
/* APB_SARADC_ADC2_DONE_INT_ST : RO ;bitpos:[30] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_ADC2_DONE_INT_ST (BIT(30))
#define APB_SARADC_ADC2_DONE_INT_ST_M (BIT(30))
#define APB_SARADC_ADC2_DONE_INT_ST_V 0x1
#define APB_SARADC_ADC2_DONE_INT_ST_S 30
/* APB_SARADC_THRES0_HIGH_INT_ST : RO ;bitpos:[29] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_THRES0_HIGH_INT_ST (BIT(29))
#define APB_SARADC_THRES0_HIGH_INT_ST_M (BIT(29))
#define APB_SARADC_THRES0_HIGH_INT_ST_V 0x1
#define APB_SARADC_THRES0_HIGH_INT_ST_S 29
/* APB_SARADC_THRES1_HIGH_INT_ST : RO ;bitpos:[28] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_THRES1_HIGH_INT_ST (BIT(28))
#define APB_SARADC_THRES1_HIGH_INT_ST_M (BIT(28))
#define APB_SARADC_THRES1_HIGH_INT_ST_V 0x1
#define APB_SARADC_THRES1_HIGH_INT_ST_S 28
/* APB_SARADC_THRES0_LOW_INT_ST : RO ;bitpos:[27] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_THRES0_LOW_INT_ST (BIT(27))
#define APB_SARADC_THRES0_LOW_INT_ST_M (BIT(27))
#define APB_SARADC_THRES0_LOW_INT_ST_V 0x1
#define APB_SARADC_THRES0_LOW_INT_ST_S 27
/* APB_SARADC_THRES1_LOW_INT_ST : RO ;bitpos:[26] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_THRES1_LOW_INT_ST (BIT(26))
#define APB_SARADC_THRES1_LOW_INT_ST_M (BIT(26))
#define APB_SARADC_THRES1_LOW_INT_ST_V 0x1
#define APB_SARADC_THRES1_LOW_INT_ST_S 26
#define APB_SARADC_INT_CLR_REG (DR_REG_APB_SARADC_BASE + 0x04C)
/* APB_SARADC_ADC1_DONE_INT_CLR : WO ;bitpos:[31] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_ADC1_DONE_INT_CLR (BIT(31))
#define APB_SARADC_ADC1_DONE_INT_CLR_M (BIT(31))
#define APB_SARADC_ADC1_DONE_INT_CLR_V 0x1
#define APB_SARADC_ADC1_DONE_INT_CLR_S 31
/* APB_SARADC_ADC2_DONE_INT_CLR : WO ;bitpos:[30] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_ADC2_DONE_INT_CLR (BIT(30))
#define APB_SARADC_ADC2_DONE_INT_CLR_M (BIT(30))
#define APB_SARADC_ADC2_DONE_INT_CLR_V 0x1
#define APB_SARADC_ADC2_DONE_INT_CLR_S 30
/* APB_SARADC_THRES0_HIGH_INT_CLR : WO ;bitpos:[29] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_THRES0_HIGH_INT_CLR (BIT(29))
#define APB_SARADC_THRES0_HIGH_INT_CLR_M (BIT(29))
#define APB_SARADC_THRES0_HIGH_INT_CLR_V 0x1
#define APB_SARADC_THRES0_HIGH_INT_CLR_S 29
/* APB_SARADC_THRES1_HIGH_INT_CLR : WO ;bitpos:[28] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_THRES1_HIGH_INT_CLR (BIT(28))
#define APB_SARADC_THRES1_HIGH_INT_CLR_M (BIT(28))
#define APB_SARADC_THRES1_HIGH_INT_CLR_V 0x1
#define APB_SARADC_THRES1_HIGH_INT_CLR_S 28
/* APB_SARADC_THRES0_LOW_INT_CLR : WO ;bitpos:[27] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_THRES0_LOW_INT_CLR (BIT(27))
#define APB_SARADC_THRES0_LOW_INT_CLR_M (BIT(27))
#define APB_SARADC_THRES0_LOW_INT_CLR_V 0x1
#define APB_SARADC_THRES0_LOW_INT_CLR_S 27
/* APB_SARADC_THRES1_LOW_INT_CLR : WO ;bitpos:[26] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_THRES1_LOW_INT_CLR (BIT(26))
#define APB_SARADC_THRES1_LOW_INT_CLR_M (BIT(26))
#define APB_SARADC_THRES1_LOW_INT_CLR_V 0x1
#define APB_SARADC_THRES1_LOW_INT_CLR_S 26
#define APB_SARADC_DMA_CONF_REG (DR_REG_APB_SARADC_BASE + 0x050)
/* APB_SARADC_APB_ADC_TRANS : R/W ;bitpos:[31] ;default: 1'd0 ; */
/*description: enable apb_adc use spi_dma*/
#define APB_SARADC_APB_ADC_TRANS (BIT(31))
#define APB_SARADC_APB_ADC_TRANS_M (BIT(31))
#define APB_SARADC_APB_ADC_TRANS_V 0x1
#define APB_SARADC_APB_ADC_TRANS_S 31
/* APB_SARADC_APB_ADC_RESET_FSM : R/W ;bitpos:[30] ;default: 1'b0 ; */
/*description: reset_apb_adc_state*/
#define APB_SARADC_APB_ADC_RESET_FSM (BIT(30))
#define APB_SARADC_APB_ADC_RESET_FSM_M (BIT(30))
#define APB_SARADC_APB_ADC_RESET_FSM_V 0x1
#define APB_SARADC_APB_ADC_RESET_FSM_S 30
/* APB_SARADC_APB_ADC_EOF_NUM : R/W ;bitpos:[15:0] ;default: 16'd255 ; */
/*description: the dma_in_suc_eof gen when sample cnt = spi_eof_num*/
#define APB_SARADC_APB_ADC_EOF_NUM 0x0000FFFF
#define APB_SARADC_APB_ADC_EOF_NUM_M ((APB_SARADC_APB_ADC_EOF_NUM_V)<<(APB_SARADC_APB_ADC_EOF_NUM_S))
#define APB_SARADC_APB_ADC_EOF_NUM_V 0xFFFF
#define APB_SARADC_APB_ADC_EOF_NUM_S 0
#define APB_SARADC_APB_ADC_CLKM_CONF_REG (DR_REG_APB_SARADC_BASE + 0x054)
/* APB_SARADC_CLK_SEL : R/W ;bitpos:[22:21] ;default: 2'b0 ; */
/*description: Set this bit to enable clk_apll*/
#define APB_SARADC_CLK_SEL 0x00000003
#define APB_SARADC_CLK_SEL_M ((APB_SARADC_CLK_SEL_V)<<(APB_SARADC_CLK_SEL_S))
#define APB_SARADC_CLK_SEL_V 0x3
#define APB_SARADC_CLK_SEL_S 21
/* APB_SARADC_CLK_EN : R/W ;bitpos:[20] ;default: 1'd0 ; */
/*description: */
#define APB_SARADC_CLK_EN (BIT(20))
#define APB_SARADC_CLK_EN_M (BIT(20))
#define APB_SARADC_CLK_EN_V 0x1
#define APB_SARADC_CLK_EN_S 20
/* APB_SARADC_CLKM_DIV_A : R/W ;bitpos:[19:14] ;default: 6'h0 ; */
/*description: Fractional clock divider denominator value*/
#define APB_SARADC_CLKM_DIV_A 0x0000003F
#define APB_SARADC_CLKM_DIV_A_M ((APB_SARADC_CLKM_DIV_A_V)<<(APB_SARADC_CLKM_DIV_A_S))
#define APB_SARADC_CLKM_DIV_A_V 0x3F
#define APB_SARADC_CLKM_DIV_A_S 14
/* APB_SARADC_CLKM_DIV_B : R/W ;bitpos:[13:8] ;default: 6'h0 ; */
/*description: Fractional clock divider numerator value*/
#define APB_SARADC_CLKM_DIV_B 0x0000003F
#define APB_SARADC_CLKM_DIV_B_M ((APB_SARADC_CLKM_DIV_B_V)<<(APB_SARADC_CLKM_DIV_B_S))
#define APB_SARADC_CLKM_DIV_B_V 0x3F
#define APB_SARADC_CLKM_DIV_B_S 8
/* APB_SARADC_CLKM_DIV_NUM : R/W ;bitpos:[7:0] ;default: 8'd4 ; */
/*description: Integral I2S clock divider value*/
#define APB_SARADC_CLKM_DIV_NUM 0x000000FF
#define APB_SARADC_CLKM_DIV_NUM_M ((APB_SARADC_CLKM_DIV_NUM_V)<<(APB_SARADC_CLKM_DIV_NUM_S))
#define APB_SARADC_CLKM_DIV_NUM_V 0xFF
#define APB_SARADC_CLKM_DIV_NUM_S 0
#define APB_SARADC_APB_TSENS_CTRL_REG (DR_REG_APB_SARADC_BASE + 0x058)
/* APB_SARADC_TSENS_PU : R/W ;bitpos:[22] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_TSENS_PU (BIT(22))
#define APB_SARADC_TSENS_PU_M (BIT(22))
#define APB_SARADC_TSENS_PU_V 0x1
#define APB_SARADC_TSENS_PU_S 22
/* APB_SARADC_TSENS_CLK_DIV : R/W ;bitpos:[21:14] ;default: 8'd6 ; */
/*description: */
#define APB_SARADC_TSENS_CLK_DIV 0x000000FF
#define APB_SARADC_TSENS_CLK_DIV_M ((APB_SARADC_TSENS_CLK_DIV_V)<<(APB_SARADC_TSENS_CLK_DIV_S))
#define APB_SARADC_TSENS_CLK_DIV_V 0xFF
#define APB_SARADC_TSENS_CLK_DIV_S 14
/* APB_SARADC_TSENS_IN_INV : R/W ;bitpos:[13] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_TSENS_IN_INV (BIT(13))
#define APB_SARADC_TSENS_IN_INV_M (BIT(13))
#define APB_SARADC_TSENS_IN_INV_V 0x1
#define APB_SARADC_TSENS_IN_INV_S 13
/* APB_SARADC_TSENS_OUT : RO ;bitpos:[7:0] ;default: 8'h0 ; */
/*description: */
#define APB_SARADC_TSENS_OUT 0x000000FF
#define APB_SARADC_TSENS_OUT_M ((APB_SARADC_TSENS_OUT_V)<<(APB_SARADC_TSENS_OUT_S))
#define APB_SARADC_TSENS_OUT_V 0xFF
#define APB_SARADC_TSENS_OUT_S 0
#define APB_SARADC_APB_TSENS_CTRL2_REG (DR_REG_APB_SARADC_BASE + 0x05C)
/* APB_SARADC_TSENS_CLK_SEL : R/W ;bitpos:[15] ;default: 1'b0 ; */
/*description: */
#define APB_SARADC_TSENS_CLK_SEL (BIT(15))
#define APB_SARADC_TSENS_CLK_SEL_M (BIT(15))
#define APB_SARADC_TSENS_CLK_SEL_V 0x1
#define APB_SARADC_TSENS_CLK_SEL_S 15
/* APB_SARADC_TSENS_CLK_INV : R/W ;bitpos:[14] ;default: 1'b1 ; */
/*description: */
#define APB_SARADC_TSENS_CLK_INV (BIT(14))
#define APB_SARADC_TSENS_CLK_INV_M (BIT(14))
#define APB_SARADC_TSENS_CLK_INV_V 0x1
#define APB_SARADC_TSENS_CLK_INV_S 14
/* APB_SARADC_TSENS_XPD_FORCE : R/W ;bitpos:[13:12] ;default: 2'b0 ; */
/*description: */
#define APB_SARADC_TSENS_XPD_FORCE 0x00000003
#define APB_SARADC_TSENS_XPD_FORCE_M ((APB_SARADC_TSENS_XPD_FORCE_V)<<(APB_SARADC_TSENS_XPD_FORCE_S))
#define APB_SARADC_TSENS_XPD_FORCE_V 0x3
#define APB_SARADC_TSENS_XPD_FORCE_S 12
/* APB_SARADC_TSENS_XPD_WAIT : R/W ;bitpos:[11:0] ;default: 12'h2 ; */
/*description: */
#define APB_SARADC_TSENS_XPD_WAIT 0x00000FFF
#define APB_SARADC_TSENS_XPD_WAIT_M ((APB_SARADC_TSENS_XPD_WAIT_V)<<(APB_SARADC_TSENS_XPD_WAIT_S))
#define APB_SARADC_TSENS_XPD_WAIT_V 0xFFF
#define APB_SARADC_TSENS_XPD_WAIT_S 0
#define APB_SARADC_CALI_REG (DR_REG_APB_SARADC_BASE + 0x060)
/* APB_SARADC_CALI_CFG : R/W ;bitpos:[16:0] ;default: 17'h8000 ; */
/*description: */
#define APB_SARADC_CALI_CFG 0x0001FFFF
#define APB_SARADC_CALI_CFG_M ((APB_SARADC_CALI_CFG_V)<<(APB_SARADC_CALI_CFG_S))
#define APB_SARADC_CALI_CFG_V 0x1FFFF
#define APB_SARADC_CALI_CFG_S 0
#define APB_SARADC_APB_CTRL_DATE_REG (DR_REG_APB_SARADC_BASE + 0x3fc)
/* APB_SARADC_DATE : R/W ;bitpos:[31:0] ;default: 32'h02007171 ; */
/*description: */
#define APB_SARADC_DATE 0xFFFFFFFF
#define APB_SARADC_DATE_M ((APB_SARADC_DATE_V)<<(APB_SARADC_DATE_S))
#define APB_SARADC_DATE_V 0xFFFFFFFF
#define APB_SARADC_DATE_S 0
#ifdef __cplusplus
}
#endif
#endif /*_SOC_APB_SARADC_REG_H_ */

View File

@ -0,0 +1,490 @@
// 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.
#ifndef _SOC_APB_SARADC_STRUCT_H_
#define _SOC_APB_SARADC_STRUCT_H_
#ifdef __cplusplus
extern "C" {
#endif
typedef volatile struct {
union {
struct {
uint32_t start_force: 1;
uint32_t start: 1;
uint32_t reserved2: 4; /*0: single mode 1: double mode 2: alternate mode*/
uint32_t sar_clk_gated: 1;
uint32_t sar_clk_div: 8; /*SAR clock divider*/
uint32_t sar_patt_len: 3; /*0 ~ 15 means length 1 ~ 16*/
uint32_t reserved18: 5;
uint32_t sar_patt_p_clear: 1; /*clear the pointer of pattern table for DIG ADC1 CTRL*/
uint32_t reserved24: 3;
uint32_t xpd_sar_force: 2; /*force option to xpd sar blocks*/
uint32_t reserved29: 1;
uint32_t wait_arb_cycle: 2; /*wait arbit signal stable after sar_done*/
};
uint32_t val;
} ctrl;
union {
struct {
uint32_t meas_num_limit: 1;
uint32_t max_meas_num: 8; /*max conversion number*/
uint32_t sar1_inv: 1; /*1: data to DIG ADC1 CTRL is inverted otherwise not*/
uint32_t sar2_inv: 1; /*1: data to DIG ADC2 CTRL is inverted otherwise not*/
uint32_t reserved11: 1; /*1: select saradc timer 0: i2s_ws trigger*/
uint32_t timer_target: 12; /*to set saradc timer target*/
uint32_t timer_en: 1; /*to enable saradc timer trigger*/
uint32_t reserved25: 7;
};
uint32_t val;
} ctrl2;
union {
struct {
uint32_t reserved0: 26;
uint32_t filter_factor1: 3;
uint32_t filter_factor0: 3;
};
uint32_t val;
} filter_ctrl1;
union {
struct {
uint32_t xpd_wait: 8;
uint32_t rstb_wait: 8;
uint32_t standby_wait: 8;
uint32_t reserved24: 8;
};
uint32_t val;
} fsm_wait;
uint32_t sar1_status; /**/
uint32_t sar2_status; /**/
union {
struct {
uint32_t sar_patt_tab1: 24; /*item 0 ~ 3 for pattern table 1 (each item one byte)*/
uint32_t reserved24: 8;
};
uint32_t val;
} sar_patt_tab[2];
union {
struct {
uint32_t reserved0: 23;
uint32_t onetime_atten: 2;
uint32_t onetime_channel: 4;
uint32_t onetime_start: 1;
uint32_t adc2_onetime_sample: 1;
uint32_t adc1_onetime_sample: 1;
};
uint32_t val;
} onetime_sample;
union {
struct {
uint32_t reserved0: 2;
uint32_t adc_arb_apb_force: 1; /*adc2 arbiter force to enableapb controller*/
uint32_t adc_arb_rtc_force: 1; /*adc2 arbiter force to enable rtc controller*/
uint32_t adc_arb_wifi_force: 1; /*adc2 arbiter force to enable wifi controller*/
uint32_t adc_arb_grant_force: 1; /*adc2 arbiter force grant*/
uint32_t adc_arb_apb_priority: 2; /*Set adc2 arbiterapb priority*/
uint32_t adc_arb_rtc_priority: 2; /*Set adc2 arbiter rtc priority*/
uint32_t adc_arb_wifi_priority: 2; /*Set adc2 arbiter wifi priority*/
uint32_t adc_arb_fix_priority: 1; /*adc2 arbiter uses fixed priority*/
uint32_t reserved13: 19;
};
uint32_t val;
} apb_adc_arb_ctrl;
union {
struct {
uint32_t reserved0: 18;
uint32_t filter_channel1: 4;
uint32_t filter_channel0: 4; /*apb_adc1_filter_factor*/
uint32_t reserved26: 5;
uint32_t filter_reset: 1; /*enable apb_adc1_filter*/
};
uint32_t val;
} filter_ctrl0;
union {
struct {
uint32_t adc1_data: 17;
uint32_t reserved17:15;
};
uint32_t val;
} apb_saradc1_data_status;
union {
struct {
uint32_t adc2_data: 17;
uint32_t reserved17:15;
};
uint32_t val;
} apb_saradc2_data_status;
union {
struct {
uint32_t thres0_channel: 4;
uint32_t reserved4: 1;
uint32_t thres0_high: 13; /*saradc1's thres0 monitor thres*/
uint32_t thres0_low: 13; /*saradc1's thres0 monitor thres*/
uint32_t reserved31: 1;
};
uint32_t val;
} thres0_ctrl;
union {
struct {
uint32_t thres1_channel: 4;
uint32_t reserved4: 1;
uint32_t thres1_high: 13; /*saradc1's thres0 monitor thres*/
uint32_t thres1_low: 13; /*saradc1's thres0 monitor thres*/
uint32_t reserved31: 1;
};
uint32_t val;
} thres1_ctrl;
union {
struct {
uint32_t reserved0: 27;
uint32_t thres_all_en: 1;
uint32_t reserved28: 2;
uint32_t thres1_en: 1;
uint32_t thres0_en: 1;
};
uint32_t val;
} thres_ctrl;
union {
struct {
uint32_t reserved0: 26;
uint32_t thres1_low: 1;
uint32_t thres0_low: 1;
uint32_t thres1_high: 1;
uint32_t thres0_high: 1;
uint32_t adc2_done: 1;
uint32_t adc1_done: 1;
};
uint32_t val;
} int_ena;
union {
struct {
uint32_t reserved0: 26;
uint32_t thres1_low: 1;
uint32_t thres0_low: 1;
uint32_t thres1_high: 1;
uint32_t thres0_high: 1;
uint32_t adc2_done: 1;
uint32_t adc1_done: 1;
};
uint32_t val;
} int_raw;
union {
struct {
uint32_t reserved0: 26;
uint32_t thres1_low: 1;
uint32_t thres0_low: 1;
uint32_t thres1_high: 1;
uint32_t thres0_high: 1;
uint32_t adc2_done: 1;
uint32_t adc1_done: 1;
};
uint32_t val;
} int_st;
union {
struct {
uint32_t reserved0: 26;
uint32_t thres1_low: 1;
uint32_t thres0_low: 1;
uint32_t thres1_high: 1;
uint32_t thres0_high: 1;
uint32_t adc2_done: 1;
uint32_t adc1_done: 1;
};
uint32_t val;
} int_clr;
union {
struct {
uint32_t apb_adc_eof_num: 16; /*the dma_in_suc_eof gen when sample cnt = spi_eof_num*/
uint32_t reserved16: 14;
uint32_t apb_adc_reset_fsm: 1; /*reset_apb_adc_state*/
uint32_t apb_adc_trans: 1; /*enable apb_adc use spi_dma*/
};
uint32_t val;
} dma_conf;
union {
struct {
uint32_t clkm_div_num: 8; /*Integral I2S clock divider value*/
uint32_t clkm_div_b: 6; /*Fractional clock divider numerator value*/
uint32_t clkm_div_a: 6; /*Fractional clock divider denominator value*/
uint32_t clk_en: 1;
uint32_t clk_sel: 2; /*Set this bit to enable clk_apll*/
uint32_t reserved23: 9;
};
uint32_t val;
} apb_adc_clkm_conf;
union {
struct {
uint32_t tsens_out: 8;
uint32_t reserved8: 5;
uint32_t tsens_in_inv: 1;
uint32_t tsens_clk_div: 8;
uint32_t tsens_pu: 1;
uint32_t reserved23: 9;
};
uint32_t val;
} apb_tsens_ctrl;
union {
struct {
uint32_t tsens_xpd_wait: 12;
uint32_t tsens_xpd_force: 2;
uint32_t tsens_clk_inv: 1;
uint32_t tsens_clk_sel: 1;
uint32_t reserved16: 16;
};
uint32_t val;
} apb_tsens_ctrl2;
union {
struct {
uint32_t cali_cfg: 17;
uint32_t reserved17:15;
};
uint32_t val;
} cali;
uint32_t reserved_64;
uint32_t reserved_68;
uint32_t reserved_6c;
uint32_t reserved_70;
uint32_t reserved_74;
uint32_t reserved_78;
uint32_t reserved_7c;
uint32_t reserved_80;
uint32_t reserved_84;
uint32_t reserved_88;
uint32_t reserved_8c;
uint32_t reserved_90;
uint32_t reserved_94;
uint32_t reserved_98;
uint32_t reserved_9c;
uint32_t reserved_a0;
uint32_t reserved_a4;
uint32_t reserved_a8;
uint32_t reserved_ac;
uint32_t reserved_b0;
uint32_t reserved_b4;
uint32_t reserved_b8;
uint32_t reserved_bc;
uint32_t reserved_c0;
uint32_t reserved_c4;
uint32_t reserved_c8;
uint32_t reserved_cc;
uint32_t reserved_d0;
uint32_t reserved_d4;
uint32_t reserved_d8;
uint32_t reserved_dc;
uint32_t reserved_e0;
uint32_t reserved_e4;
uint32_t reserved_e8;
uint32_t reserved_ec;
uint32_t reserved_f0;
uint32_t reserved_f4;
uint32_t reserved_f8;
uint32_t reserved_fc;
uint32_t reserved_100;
uint32_t reserved_104;
uint32_t reserved_108;
uint32_t reserved_10c;
uint32_t reserved_110;
uint32_t reserved_114;
uint32_t reserved_118;
uint32_t reserved_11c;
uint32_t reserved_120;
uint32_t reserved_124;
uint32_t reserved_128;
uint32_t reserved_12c;
uint32_t reserved_130;
uint32_t reserved_134;
uint32_t reserved_138;
uint32_t reserved_13c;
uint32_t reserved_140;
uint32_t reserved_144;
uint32_t reserved_148;
uint32_t reserved_14c;
uint32_t reserved_150;
uint32_t reserved_154;
uint32_t reserved_158;
uint32_t reserved_15c;
uint32_t reserved_160;
uint32_t reserved_164;
uint32_t reserved_168;
uint32_t reserved_16c;
uint32_t reserved_170;
uint32_t reserved_174;
uint32_t reserved_178;
uint32_t reserved_17c;
uint32_t reserved_180;
uint32_t reserved_184;
uint32_t reserved_188;
uint32_t reserved_18c;
uint32_t reserved_190;
uint32_t reserved_194;
uint32_t reserved_198;
uint32_t reserved_19c;
uint32_t reserved_1a0;
uint32_t reserved_1a4;
uint32_t reserved_1a8;
uint32_t reserved_1ac;
uint32_t reserved_1b0;
uint32_t reserved_1b4;
uint32_t reserved_1b8;
uint32_t reserved_1bc;
uint32_t reserved_1c0;
uint32_t reserved_1c4;
uint32_t reserved_1c8;
uint32_t reserved_1cc;
uint32_t reserved_1d0;
uint32_t reserved_1d4;
uint32_t reserved_1d8;
uint32_t reserved_1dc;
uint32_t reserved_1e0;
uint32_t reserved_1e4;
uint32_t reserved_1e8;
uint32_t reserved_1ec;
uint32_t reserved_1f0;
uint32_t reserved_1f4;
uint32_t reserved_1f8;
uint32_t reserved_1fc;
uint32_t reserved_200;
uint32_t reserved_204;
uint32_t reserved_208;
uint32_t reserved_20c;
uint32_t reserved_210;
uint32_t reserved_214;
uint32_t reserved_218;
uint32_t reserved_21c;
uint32_t reserved_220;
uint32_t reserved_224;
uint32_t reserved_228;
uint32_t reserved_22c;
uint32_t reserved_230;
uint32_t reserved_234;
uint32_t reserved_238;
uint32_t reserved_23c;
uint32_t reserved_240;
uint32_t reserved_244;
uint32_t reserved_248;
uint32_t reserved_24c;
uint32_t reserved_250;
uint32_t reserved_254;
uint32_t reserved_258;
uint32_t reserved_25c;
uint32_t reserved_260;
uint32_t reserved_264;
uint32_t reserved_268;
uint32_t reserved_26c;
uint32_t reserved_270;
uint32_t reserved_274;
uint32_t reserved_278;
uint32_t reserved_27c;
uint32_t reserved_280;
uint32_t reserved_284;
uint32_t reserved_288;
uint32_t reserved_28c;
uint32_t reserved_290;
uint32_t reserved_294;
uint32_t reserved_298;
uint32_t reserved_29c;
uint32_t reserved_2a0;
uint32_t reserved_2a4;
uint32_t reserved_2a8;
uint32_t reserved_2ac;
uint32_t reserved_2b0;
uint32_t reserved_2b4;
uint32_t reserved_2b8;
uint32_t reserved_2bc;
uint32_t reserved_2c0;
uint32_t reserved_2c4;
uint32_t reserved_2c8;
uint32_t reserved_2cc;
uint32_t reserved_2d0;
uint32_t reserved_2d4;
uint32_t reserved_2d8;
uint32_t reserved_2dc;
uint32_t reserved_2e0;
uint32_t reserved_2e4;
uint32_t reserved_2e8;
uint32_t reserved_2ec;
uint32_t reserved_2f0;
uint32_t reserved_2f4;
uint32_t reserved_2f8;
uint32_t reserved_2fc;
uint32_t reserved_300;
uint32_t reserved_304;
uint32_t reserved_308;
uint32_t reserved_30c;
uint32_t reserved_310;
uint32_t reserved_314;
uint32_t reserved_318;
uint32_t reserved_31c;
uint32_t reserved_320;
uint32_t reserved_324;
uint32_t reserved_328;
uint32_t reserved_32c;
uint32_t reserved_330;
uint32_t reserved_334;
uint32_t reserved_338;
uint32_t reserved_33c;
uint32_t reserved_340;
uint32_t reserved_344;
uint32_t reserved_348;
uint32_t reserved_34c;
uint32_t reserved_350;
uint32_t reserved_354;
uint32_t reserved_358;
uint32_t reserved_35c;
uint32_t reserved_360;
uint32_t reserved_364;
uint32_t reserved_368;
uint32_t reserved_36c;
uint32_t reserved_370;
uint32_t reserved_374;
uint32_t reserved_378;
uint32_t reserved_37c;
uint32_t reserved_380;
uint32_t reserved_384;
uint32_t reserved_388;
uint32_t reserved_38c;
uint32_t reserved_390;
uint32_t reserved_394;
uint32_t reserved_398;
uint32_t reserved_39c;
uint32_t reserved_3a0;
uint32_t reserved_3a4;
uint32_t reserved_3a8;
uint32_t reserved_3ac;
uint32_t reserved_3b0;
uint32_t reserved_3b4;
uint32_t reserved_3b8;
uint32_t reserved_3bc;
uint32_t reserved_3c0;
uint32_t reserved_3c4;
uint32_t reserved_3c8;
uint32_t reserved_3cc;
uint32_t reserved_3d0;
uint32_t reserved_3d4;
uint32_t reserved_3d8;
uint32_t reserved_3dc;
uint32_t reserved_3e0;
uint32_t reserved_3e4;
uint32_t reserved_3e8;
uint32_t reserved_3ec;
uint32_t reserved_3f0;
uint32_t reserved_3f4;
uint32_t reserved_3f8;
uint32_t apb_ctrl_date; /**/
} apb_saradc_dev_t;
extern apb_saradc_dev_t APB_SARADC;
#ifdef __cplusplus
}
#endif
#endif /* _SOC_APB_SARADC_STRUCT_H_ */

View File

@ -0,0 +1,691 @@
// 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.
#ifndef _SOC_ASSIST_DEBUG_REG_H_
#define _SOC_ASSIST_DEBUG_REG_H_
#ifdef __cplusplus
extern "C" {
#endif
#include "soc.h"
#define ASSIST_DEBUG_CORE_0_INTR_ENA_REG (DR_REG_ASSIST_DEBUG_BASE + 0x000)
/* ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_ENA : R/W ;bitpos:[11] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_ENA (BIT(11))
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_ENA_M (BIT(11))
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_ENA_V 0x1
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_ENA_S 11
/* ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_ENA : R/W ;bitpos:[10] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_ENA (BIT(10))
#define ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_ENA_M (BIT(10))
#define ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_ENA_V 0x1
#define ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_ENA_S 10
/* ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_ENA : R/W ;bitpos:[9] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_ENA (BIT(9))
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_ENA_M (BIT(9))
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_ENA_V 0x1
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_ENA_S 9
/* ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_ENA : R/W ;bitpos:[8] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_ENA (BIT(8))
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_ENA_M (BIT(8))
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_ENA_V 0x1
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_ENA_S 8
/* ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_ENA : R/W ;bitpos:[7] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_ENA (BIT(7))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_ENA_M (BIT(7))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_ENA_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_ENA_S 7
/* ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_ENA : R/W ;bitpos:[6] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_ENA (BIT(6))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_ENA_M (BIT(6))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_ENA_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_ENA_S 6
/* ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_ENA : R/W ;bitpos:[5] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_ENA (BIT(5))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_ENA_M (BIT(5))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_ENA_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_ENA_S 5
/* ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_ENA : R/W ;bitpos:[4] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_ENA (BIT(4))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_ENA_M (BIT(4))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_ENA_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_ENA_S 4
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_ENA : R/W ;bitpos:[3] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_ENA (BIT(3))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_ENA_M (BIT(3))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_ENA_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_ENA_S 3
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_ENA : R/W ;bitpos:[2] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_ENA (BIT(2))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_ENA_M (BIT(2))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_ENA_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_ENA_S 2
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_ENA : R/W ;bitpos:[1] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_ENA (BIT(1))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_ENA_M (BIT(1))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_ENA_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_ENA_S 1
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_ENA : R/W ;bitpos:[0] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_ENA (BIT(0))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_ENA_M (BIT(0))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_ENA_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_ENA_S 0
#define ASSIST_DEBUG_CORE_0_INTR_RAW_REG (DR_REG_ASSIST_DEBUG_BASE + 0x004)
/* ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_RAW : RO ;bitpos:[11] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_RAW (BIT(11))
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_RAW_M (BIT(11))
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_RAW_V 0x1
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_RAW_S 11
/* ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_RAW : RO ;bitpos:[10] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_RAW (BIT(10))
#define ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_RAW_M (BIT(10))
#define ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_RAW_V 0x1
#define ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_RAW_S 10
/* ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_RAW : RO ;bitpos:[9] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_RAW (BIT(9))
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_RAW_M (BIT(9))
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_RAW_V 0x1
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_RAW_S 9
/* ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_RAW : RO ;bitpos:[8] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_RAW (BIT(8))
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_RAW_M (BIT(8))
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_RAW_V 0x1
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_RAW_S 8
/* ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_RAW : RO ;bitpos:[7] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_RAW (BIT(7))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_RAW_M (BIT(7))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_RAW_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_RAW_S 7
/* ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_RAW : RO ;bitpos:[6] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_RAW (BIT(6))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_RAW_M (BIT(6))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_RAW_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_RAW_S 6
/* ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_RAW : RO ;bitpos:[5] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_RAW (BIT(5))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_RAW_M (BIT(5))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_RAW_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_RAW_S 5
/* ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_RAW : RO ;bitpos:[4] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_RAW (BIT(4))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_RAW_M (BIT(4))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_RAW_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_RAW_S 4
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_RAW : RO ;bitpos:[3] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_RAW (BIT(3))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_RAW_M (BIT(3))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_RAW_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_RAW_S 3
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_RAW : RO ;bitpos:[2] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_RAW (BIT(2))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_RAW_M (BIT(2))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_RAW_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_RAW_S 2
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_RAW : RO ;bitpos:[1] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_RAW (BIT(1))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_RAW_M (BIT(1))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_RAW_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_RAW_S 1
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_RAW : RO ;bitpos:[0] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_RAW (BIT(0))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_RAW_M (BIT(0))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_RAW_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_RAW_S 0
#define ASSIST_DEBUG_CORE_0_INTR_RLS_REG (DR_REG_ASSIST_DEBUG_BASE + 0x008)
/* ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_RLS : R/W ;bitpos:[11] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_RLS (BIT(11))
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_RLS_M (BIT(11))
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_RLS_V 0x1
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_RLS_S 11
/* ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_RLS : R/W ;bitpos:[10] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_RLS (BIT(10))
#define ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_RLS_M (BIT(10))
#define ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_RLS_V 0x1
#define ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_RLS_S 10
/* ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_RLS : R/W ;bitpos:[9] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_RLS (BIT(9))
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_RLS_M (BIT(9))
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_RLS_V 0x1
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_RLS_S 9
/* ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_RLS : R/W ;bitpos:[8] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_RLS (BIT(8))
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_RLS_M (BIT(8))
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_RLS_V 0x1
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_RLS_S 8
/* ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_RLS : R/W ;bitpos:[7] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_RLS (BIT(7))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_RLS_M (BIT(7))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_RLS_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_RLS_S 7
/* ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_RLS : R/W ;bitpos:[6] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_RLS (BIT(6))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_RLS_M (BIT(6))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_RLS_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_RLS_S 6
/* ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_RLS : R/W ;bitpos:[5] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_RLS (BIT(5))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_RLS_M (BIT(5))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_RLS_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_RLS_S 5
/* ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_RLS : R/W ;bitpos:[4] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_RLS (BIT(4))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_RLS_M (BIT(4))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_RLS_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_RLS_S 4
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_RLS : R/W ;bitpos:[3] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_RLS (BIT(3))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_RLS_M (BIT(3))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_RLS_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_RLS_S 3
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_RLS : R/W ;bitpos:[2] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_RLS (BIT(2))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_RLS_M (BIT(2))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_RLS_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_RLS_S 2
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_RLS : R/W ;bitpos:[1] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_RLS (BIT(1))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_RLS_M (BIT(1))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_RLS_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_RLS_S 1
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_RLS : R/W ;bitpos:[0] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_RLS (BIT(0))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_RLS_M (BIT(0))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_RLS_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_RLS_S 0
#define ASSIST_DEBUG_CORE_0_INTR_CLR_REG (DR_REG_ASSIST_DEBUG_BASE + 0x00C)
/* ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_CLR : R/W ;bitpos:[11] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_CLR (BIT(11))
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_CLR_M (BIT(11))
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_CLR_V 0x1
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_CLR_S 11
/* ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_CLR : R/W ;bitpos:[10] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_CLR (BIT(10))
#define ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_CLR_M (BIT(10))
#define ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_CLR_V 0x1
#define ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_CLR_S 10
/* ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_CLR : R/W ;bitpos:[9] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_CLR (BIT(9))
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_CLR_M (BIT(9))
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_CLR_V 0x1
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MAX_CLR_S 9
/* ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_CLR : R/W ;bitpos:[8] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_CLR (BIT(8))
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_CLR_M (BIT(8))
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_CLR_V 0x1
#define ASSIST_DEBUG_CORE_0_SP_SPILL_MIN_CLR_S 8
/* ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_CLR : R/W ;bitpos:[7] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_CLR (BIT(7))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_CLR_M (BIT(7))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_CLR_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_WR_CLR_S 7
/* ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_CLR : R/W ;bitpos:[6] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_CLR (BIT(6))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_CLR_M (BIT(6))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_CLR_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_RD_CLR_S 6
/* ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_CLR : R/W ;bitpos:[5] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_CLR (BIT(5))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_CLR_M (BIT(5))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_CLR_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_WR_CLR_S 5
/* ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_CLR : R/W ;bitpos:[4] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_CLR (BIT(4))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_CLR_M (BIT(4))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_CLR_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_RD_CLR_S 4
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_CLR : R/W ;bitpos:[3] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_CLR (BIT(3))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_CLR_M (BIT(3))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_CLR_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_WR_CLR_S 3
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_CLR : R/W ;bitpos:[2] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_CLR (BIT(2))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_CLR_M (BIT(2))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_CLR_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_RD_CLR_S 2
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_CLR : R/W ;bitpos:[1] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_CLR (BIT(1))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_CLR_M (BIT(1))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_CLR_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_WR_CLR_S 1
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_CLR : R/W ;bitpos:[0] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_CLR (BIT(0))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_CLR_M (BIT(0))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_CLR_V 0x1
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_RD_CLR_S 0
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_MIN_REG (DR_REG_ASSIST_DEBUG_BASE + 0x010)
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_MIN : R/W ;bitpos:[31:0] ;default: ~32'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_MIN 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_MIN_M ((ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_MIN_V)<<(ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_MIN_S))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_MIN_V 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_MIN_S 0
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_MAX_REG (DR_REG_ASSIST_DEBUG_BASE + 0x014)
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_MAX : R/W ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_MAX 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_MAX_M ((ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_MAX_V)<<(ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_MAX_S))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_MAX_V 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_0_MAX_S 0
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_MIN_REG (DR_REG_ASSIST_DEBUG_BASE + 0x018)
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_MIN : R/W ;bitpos:[31:0] ;default: ~32'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_MIN 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_MIN_M ((ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_MIN_V)<<(ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_MIN_S))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_MIN_V 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_MIN_S 0
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_MAX_REG (DR_REG_ASSIST_DEBUG_BASE + 0x01C)
/* ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_MAX : R/W ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_MAX 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_MAX_M ((ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_MAX_V)<<(ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_MAX_S))
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_MAX_V 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_DRAM0_1_MAX_S 0
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_MIN_REG (DR_REG_ASSIST_DEBUG_BASE + 0x020)
/* ASSIST_DEBUG_CORE_0_AREA_PIF_0_MIN : R/W ;bitpos:[31:0] ;default: ~32'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_MIN 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_MIN_M ((ASSIST_DEBUG_CORE_0_AREA_PIF_0_MIN_V)<<(ASSIST_DEBUG_CORE_0_AREA_PIF_0_MIN_S))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_MIN_V 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_MIN_S 0
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_MAX_REG (DR_REG_ASSIST_DEBUG_BASE + 0x024)
/* ASSIST_DEBUG_CORE_0_AREA_PIF_0_MAX : R/W ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_MAX 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_MAX_M ((ASSIST_DEBUG_CORE_0_AREA_PIF_0_MAX_V)<<(ASSIST_DEBUG_CORE_0_AREA_PIF_0_MAX_S))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_MAX_V 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_PIF_0_MAX_S 0
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_MIN_REG (DR_REG_ASSIST_DEBUG_BASE + 0x028)
/* ASSIST_DEBUG_CORE_0_AREA_PIF_1_MIN : R/W ;bitpos:[31:0] ;default: ~32'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_MIN 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_MIN_M ((ASSIST_DEBUG_CORE_0_AREA_PIF_1_MIN_V)<<(ASSIST_DEBUG_CORE_0_AREA_PIF_1_MIN_S))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_MIN_V 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_MIN_S 0
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_MAX_REG (DR_REG_ASSIST_DEBUG_BASE + 0x02C)
/* ASSIST_DEBUG_CORE_0_AREA_PIF_1_MAX : R/W ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_MAX 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_MAX_M ((ASSIST_DEBUG_CORE_0_AREA_PIF_1_MAX_V)<<(ASSIST_DEBUG_CORE_0_AREA_PIF_1_MAX_S))
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_MAX_V 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_PIF_1_MAX_S 0
#define ASSIST_DEBUG_CORE_0_AREA_PC_REG (DR_REG_ASSIST_DEBUG_BASE + 0x030)
/* ASSIST_DEBUG_CORE_0_AREA_PC : RO ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_PC 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_PC_M ((ASSIST_DEBUG_CORE_0_AREA_PC_V)<<(ASSIST_DEBUG_CORE_0_AREA_PC_S))
#define ASSIST_DEBUG_CORE_0_AREA_PC_V 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_PC_S 0
#define ASSIST_DEBUG_CORE_0_AREA_SP_REG (DR_REG_ASSIST_DEBUG_BASE + 0x034)
/* ASSIST_DEBUG_CORE_0_AREA_SP : RO ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_AREA_SP 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_SP_M ((ASSIST_DEBUG_CORE_0_AREA_SP_V)<<(ASSIST_DEBUG_CORE_0_AREA_SP_S))
#define ASSIST_DEBUG_CORE_0_AREA_SP_V 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_AREA_SP_S 0
#define ASSIST_DEBUG_CORE_0_SP_MIN_REG (DR_REG_ASSIST_DEBUG_BASE + 0x038)
/* ASSIST_DEBUG_CORE_0_SP_MIN : RW ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_SP_MIN 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_SP_MIN_M ((ASSIST_DEBUG_CORE_0_SP_MIN_V)<<(ASSIST_DEBUG_CORE_0_SP_MIN_S))
#define ASSIST_DEBUG_CORE_0_SP_MIN_V 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_SP_MIN_S 0
#define ASSIST_DEBUG_CORE_0_SP_MAX_REG (DR_REG_ASSIST_DEBUG_BASE + 0x03C)
/* ASSIST_DEBUG_CORE_0_SP_MAX : RW ;bitpos:[31:0] ;default: ~32'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_SP_MAX 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_SP_MAX_M ((ASSIST_DEBUG_CORE_0_SP_MAX_V)<<(ASSIST_DEBUG_CORE_0_SP_MAX_S))
#define ASSIST_DEBUG_CORE_0_SP_MAX_V 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_SP_MAX_S 0
#define ASSIST_DEBUG_CORE_0_SP_PC_REG (DR_REG_ASSIST_DEBUG_BASE + 0x040)
/* ASSIST_DEBUG_CORE_0_SP_PC : RO ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_SP_PC 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_SP_PC_M ((ASSIST_DEBUG_CORE_0_SP_PC_V)<<(ASSIST_DEBUG_CORE_0_SP_PC_S))
#define ASSIST_DEBUG_CORE_0_SP_PC_V 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_SP_PC_S 0
#define ASSIST_DEBUG_CORE_0_RCD_EN_REG (DR_REG_ASSIST_DEBUG_BASE + 0x044)
/* ASSIST_DEBUG_CORE_0_RCD_PDEBUGEN : RW ;bitpos:[1] ;default: 1'b0 ; */
/*description: enable CPU Pdebug function if enable CPU will update PdebugPC*/
#define ASSIST_DEBUG_CORE_0_RCD_PDEBUGEN (BIT(1))
#define ASSIST_DEBUG_CORE_0_RCD_PDEBUGEN_M (BIT(1))
#define ASSIST_DEBUG_CORE_0_RCD_PDEBUGEN_V 0x1
#define ASSIST_DEBUG_CORE_0_RCD_PDEBUGEN_S 1
/* ASSIST_DEBUG_CORE_0_RCD_RECORDEN : RW ;bitpos:[0] ;default: 1'b0 ; */
/*description: enable recording function if enable assist_debug will update
PdebugPC so you can read it*/
#define ASSIST_DEBUG_CORE_0_RCD_RECORDEN (BIT(0))
#define ASSIST_DEBUG_CORE_0_RCD_RECORDEN_M (BIT(0))
#define ASSIST_DEBUG_CORE_0_RCD_RECORDEN_V 0x1
#define ASSIST_DEBUG_CORE_0_RCD_RECORDEN_S 0
#define ASSIST_DEBUG_CORE_0_RCD_PDEBUGPC_REG (DR_REG_ASSIST_DEBUG_BASE + 0x048)
/* ASSIST_DEBUG_CORE_0_RCD_PDEBUGPC : RO ;bitpos:[31:0] ;default: 32'h0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_RCD_PDEBUGPC 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_RCD_PDEBUGPC_M ((ASSIST_DEBUG_CORE_0_RCD_PDEBUGPC_V)<<(ASSIST_DEBUG_CORE_0_RCD_PDEBUGPC_S))
#define ASSIST_DEBUG_CORE_0_RCD_PDEBUGPC_V 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_RCD_PDEBUGPC_S 0
#define ASSIST_DEBUG_CORE_0_RCD_PDEBUGSP_REG (DR_REG_ASSIST_DEBUG_BASE + 0x04C)
/* ASSIST_DEBUG_CORE_0_RCD_PDEBUGSP : RO ;bitpos:[31:0] ;default: 32'h0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_RCD_PDEBUGSP 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_RCD_PDEBUGSP_M ((ASSIST_DEBUG_CORE_0_RCD_PDEBUGSP_V)<<(ASSIST_DEBUG_CORE_0_RCD_PDEBUGSP_S))
#define ASSIST_DEBUG_CORE_0_RCD_PDEBUGSP_V 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_RCD_PDEBUGSP_S 0
#define ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_0_REG (DR_REG_ASSIST_DEBUG_BASE + 0x050)
/* ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_LOADSTORE_0 : RO ;bitpos:[25] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_LOADSTORE_0 (BIT(25))
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_LOADSTORE_0_M (BIT(25))
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_LOADSTORE_0_V 0x1
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_LOADSTORE_0_S 25
/* ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_WR_0 : RO ;bitpos:[24] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_WR_0 (BIT(24))
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_WR_0_M (BIT(24))
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_WR_0_V 0x1
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_WR_0_S 24
/* ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_ADDR_0 : RO ;bitpos:[23:0] ;default: 24'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_ADDR_0 0x00FFFFFF
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_ADDR_0_M ((ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_ADDR_0_V)<<(ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_ADDR_0_S))
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_ADDR_0_V 0xFFFFFF
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_ADDR_0_S 0
#define ASSIST_DEBUG_CORE_0_IRAM0_EXCEPTION_MONITOR_1_REG (DR_REG_ASSIST_DEBUG_BASE + 0x054)
/* ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_LOADSTORE_1 : RO ;bitpos:[25] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_LOADSTORE_1 (BIT(25))
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_LOADSTORE_1_M (BIT(25))
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_LOADSTORE_1_V 0x1
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_LOADSTORE_1_S 25
/* ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_WR_1 : RO ;bitpos:[24] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_WR_1 (BIT(24))
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_WR_1_M (BIT(24))
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_WR_1_V 0x1
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_WR_1_S 24
/* ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_ADDR_1 : RO ;bitpos:[23:0] ;default: 24'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_ADDR_1 0x00FFFFFF
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_ADDR_1_M ((ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_ADDR_1_V)<<(ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_ADDR_1_S))
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_ADDR_1_V 0xFFFFFF
#define ASSIST_DEBUG_CORE_0_IRAM0_RECORDING_ADDR_1_S 0
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_0_REG (DR_REG_ASSIST_DEBUG_BASE + 0x058)
/* ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_BYTEEN_0 : RO ;bitpos:[28:25] ;default: 4'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_BYTEEN_0 0x0000000F
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_BYTEEN_0_M ((ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_BYTEEN_0_V)<<(ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_BYTEEN_0_S))
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_BYTEEN_0_V 0xF
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_BYTEEN_0_S 25
/* ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_WR_0 : RO ;bitpos:[24] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_WR_0 (BIT(24))
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_WR_0_M (BIT(24))
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_WR_0_V 0x1
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_WR_0_S 24
/* ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_ADDR_0 : RO ;bitpos:[23:0] ;default: 24'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_ADDR_0 0x00FFFFFF
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_ADDR_0_M ((ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_ADDR_0_V)<<(ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_ADDR_0_S))
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_ADDR_0_V 0xFFFFFF
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_ADDR_0_S 0
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_1_REG (DR_REG_ASSIST_DEBUG_BASE + 0x05C)
/* ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_PC_0 : RO ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_PC_0 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_PC_0_M ((ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_PC_0_V)<<(ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_PC_0_S))
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_PC_0_V 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_PC_0_S 0
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_2_REG (DR_REG_ASSIST_DEBUG_BASE + 0x060)
/* ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_BYTEEN_1 : RO ;bitpos:[28:25] ;default: 4'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_BYTEEN_1 0x0000000F
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_BYTEEN_1_M ((ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_BYTEEN_1_V)<<(ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_BYTEEN_1_S))
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_BYTEEN_1_V 0xF
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_BYTEEN_1_S 25
/* ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_WR_1 : RO ;bitpos:[24] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_WR_1 (BIT(24))
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_WR_1_M (BIT(24))
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_WR_1_V 0x1
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_WR_1_S 24
/* ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_ADDR_1 : RO ;bitpos:[23:0] ;default: 24'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_ADDR_1 0x00FFFFFF
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_ADDR_1_M ((ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_ADDR_1_V)<<(ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_ADDR_1_S))
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_ADDR_1_V 0xFFFFFF
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_ADDR_1_S 0
#define ASSIST_DEBUG_CORE_0_DRAM0_EXCEPTION_MONITOR_3_REG (DR_REG_ASSIST_DEBUG_BASE + 0x064)
/* ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_PC_1 : RO ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_PC_1 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_PC_1_M ((ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_PC_1_V)<<(ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_PC_1_S))
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_PC_1_V 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_DRAM0_RECORDING_PC_1_S 0
#define ASSIST_DEBUG_CORE_X_IRAM0_DRAM0_EXCEPTION_MONITOR_0_REG (DR_REG_ASSIST_DEBUG_BASE + 0x068)
/* ASSIST_DEBUG_CORE_X_IRAM0_DRAM0_LIMIT_CYCLE_0 : R/W ;bitpos:[19:0] ;default: 20'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_X_IRAM0_DRAM0_LIMIT_CYCLE_0 0x000FFFFF
#define ASSIST_DEBUG_CORE_X_IRAM0_DRAM0_LIMIT_CYCLE_0_M ((ASSIST_DEBUG_CORE_X_IRAM0_DRAM0_LIMIT_CYCLE_0_V)<<(ASSIST_DEBUG_CORE_X_IRAM0_DRAM0_LIMIT_CYCLE_0_S))
#define ASSIST_DEBUG_CORE_X_IRAM0_DRAM0_LIMIT_CYCLE_0_V 0xFFFFF
#define ASSIST_DEBUG_CORE_X_IRAM0_DRAM0_LIMIT_CYCLE_0_S 0
#define ASSIST_DEBUG_CORE_X_IRAM0_DRAM0_EXCEPTION_MONITOR_1_REG (DR_REG_ASSIST_DEBUG_BASE + 0x06C)
/* ASSIST_DEBUG_CORE_X_IRAM0_DRAM0_LIMIT_CYCLE_1 : R/W ;bitpos:[19:0] ;default: 20'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_X_IRAM0_DRAM0_LIMIT_CYCLE_1 0x000FFFFF
#define ASSIST_DEBUG_CORE_X_IRAM0_DRAM0_LIMIT_CYCLE_1_M ((ASSIST_DEBUG_CORE_X_IRAM0_DRAM0_LIMIT_CYCLE_1_V)<<(ASSIST_DEBUG_CORE_X_IRAM0_DRAM0_LIMIT_CYCLE_1_S))
#define ASSIST_DEBUG_CORE_X_IRAM0_DRAM0_LIMIT_CYCLE_1_V 0xFFFFF
#define ASSIST_DEBUG_CORE_X_IRAM0_DRAM0_LIMIT_CYCLE_1_S 0
#define ASSIST_DEBUG_LOG_SETTING_REG (DR_REG_ASSIST_DEBUG_BASE + 0x070)
/* ASSIST_DEBUG_LOG_MEM_LOOP_ENABLE : R/W ;bitpos:[7] ;default: 1'b1 ; */
/*description: */
#define ASSIST_DEBUG_LOG_MEM_LOOP_ENABLE (BIT(7))
#define ASSIST_DEBUG_LOG_MEM_LOOP_ENABLE_M (BIT(7))
#define ASSIST_DEBUG_LOG_MEM_LOOP_ENABLE_V 0x1
#define ASSIST_DEBUG_LOG_MEM_LOOP_ENABLE_S 7
/* ASSIST_DEBUG_LOG_MODE : R/W ;bitpos:[6:3] ;default: 4'b0 ; */
/*description: */
#define ASSIST_DEBUG_LOG_MODE 0x0000000F
#define ASSIST_DEBUG_LOG_MODE_M ((ASSIST_DEBUG_LOG_MODE_V)<<(ASSIST_DEBUG_LOG_MODE_S))
#define ASSIST_DEBUG_LOG_MODE_V 0xF
#define ASSIST_DEBUG_LOG_MODE_S 3
/* ASSIST_DEBUG_LOG_ENA : R/W ;bitpos:[2:0] ;default: 3'b0 ; */
/*description: */
#define ASSIST_DEBUG_LOG_ENA 0x00000007
#define ASSIST_DEBUG_LOG_ENA_M ((ASSIST_DEBUG_LOG_ENA_V)<<(ASSIST_DEBUG_LOG_ENA_S))
#define ASSIST_DEBUG_LOG_ENA_V 0x7
#define ASSIST_DEBUG_LOG_ENA_S 0
#define ASSIST_DEBUG_LOG_DATA_0_REG (DR_REG_ASSIST_DEBUG_BASE + 0x074)
/* ASSIST_DEBUG_LOG_DATA_0 : R/W ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define ASSIST_DEBUG_LOG_DATA_0 0xFFFFFFFF
#define ASSIST_DEBUG_LOG_DATA_0_M ((ASSIST_DEBUG_LOG_DATA_0_V)<<(ASSIST_DEBUG_LOG_DATA_0_S))
#define ASSIST_DEBUG_LOG_DATA_0_V 0xFFFFFFFF
#define ASSIST_DEBUG_LOG_DATA_0_S 0
#define ASSIST_DEBUG_LOG_DATA_MASK_REG (DR_REG_ASSIST_DEBUG_BASE + 0x078)
/* ASSIST_DEBUG_LOG_DATA_SIZE : R/W ;bitpos:[15:0] ;default: 16'b0 ; */
/*description: */
#define ASSIST_DEBUG_LOG_DATA_SIZE 0x0000FFFF
#define ASSIST_DEBUG_LOG_DATA_SIZE_M ((ASSIST_DEBUG_LOG_DATA_SIZE_V)<<(ASSIST_DEBUG_LOG_DATA_SIZE_S))
#define ASSIST_DEBUG_LOG_DATA_SIZE_V 0xFFFF
#define ASSIST_DEBUG_LOG_DATA_SIZE_S 0
#define ASSIST_DEBUG_LOG_MIN_REG (DR_REG_ASSIST_DEBUG_BASE + 0x07C)
/* ASSIST_DEBUG_LOG_MIN : R/W ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define ASSIST_DEBUG_LOG_MIN 0xFFFFFFFF
#define ASSIST_DEBUG_LOG_MIN_M ((ASSIST_DEBUG_LOG_MIN_V)<<(ASSIST_DEBUG_LOG_MIN_S))
#define ASSIST_DEBUG_LOG_MIN_V 0xFFFFFFFF
#define ASSIST_DEBUG_LOG_MIN_S 0
#define ASSIST_DEBUG_LOG_MAX_REG (DR_REG_ASSIST_DEBUG_BASE + 0x080)
/* ASSIST_DEBUG_LOG_MAX : R/W ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define ASSIST_DEBUG_LOG_MAX 0xFFFFFFFF
#define ASSIST_DEBUG_LOG_MAX_M ((ASSIST_DEBUG_LOG_MAX_V)<<(ASSIST_DEBUG_LOG_MAX_S))
#define ASSIST_DEBUG_LOG_MAX_V 0xFFFFFFFF
#define ASSIST_DEBUG_LOG_MAX_S 0
#define ASSIST_DEBUG_LOG_MEM_START_REG (DR_REG_ASSIST_DEBUG_BASE + 0x084)
/* ASSIST_DEBUG_LOG_MEM_START : R/W ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define ASSIST_DEBUG_LOG_MEM_START 0xFFFFFFFF
#define ASSIST_DEBUG_LOG_MEM_START_M ((ASSIST_DEBUG_LOG_MEM_START_V)<<(ASSIST_DEBUG_LOG_MEM_START_S))
#define ASSIST_DEBUG_LOG_MEM_START_V 0xFFFFFFFF
#define ASSIST_DEBUG_LOG_MEM_START_S 0
#define ASSIST_DEBUG_LOG_MEM_END_REG (DR_REG_ASSIST_DEBUG_BASE + 0x088)
/* ASSIST_DEBUG_LOG_MEM_END : R/W ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define ASSIST_DEBUG_LOG_MEM_END 0xFFFFFFFF
#define ASSIST_DEBUG_LOG_MEM_END_M ((ASSIST_DEBUG_LOG_MEM_END_V)<<(ASSIST_DEBUG_LOG_MEM_END_S))
#define ASSIST_DEBUG_LOG_MEM_END_V 0xFFFFFFFF
#define ASSIST_DEBUG_LOG_MEM_END_S 0
#define ASSIST_DEBUG_LOG_MEM_WRITING_ADDR_REG (DR_REG_ASSIST_DEBUG_BASE + 0x08C)
/* ASSIST_DEBUG_LOG_MEM_WRITING_ADDR : RO ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define ASSIST_DEBUG_LOG_MEM_WRITING_ADDR 0xFFFFFFFF
#define ASSIST_DEBUG_LOG_MEM_WRITING_ADDR_M ((ASSIST_DEBUG_LOG_MEM_WRITING_ADDR_V)<<(ASSIST_DEBUG_LOG_MEM_WRITING_ADDR_S))
#define ASSIST_DEBUG_LOG_MEM_WRITING_ADDR_V 0xFFFFFFFF
#define ASSIST_DEBUG_LOG_MEM_WRITING_ADDR_S 0
#define ASSIST_DEBUG_LOG_MEM_FULL_FLAG_REG (DR_REG_ASSIST_DEBUG_BASE + 0x090)
/* ASSIST_DEBUG_CLR_LOG_MEM_FULL_FLAG : R/W ;bitpos:[1] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CLR_LOG_MEM_FULL_FLAG (BIT(1))
#define ASSIST_DEBUG_CLR_LOG_MEM_FULL_FLAG_M (BIT(1))
#define ASSIST_DEBUG_CLR_LOG_MEM_FULL_FLAG_V 0x1
#define ASSIST_DEBUG_CLR_LOG_MEM_FULL_FLAG_S 1
/* ASSIST_DEBUG_LOG_MEM_FULL_FLAG : RO ;bitpos:[0] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_LOG_MEM_FULL_FLAG (BIT(0))
#define ASSIST_DEBUG_LOG_MEM_FULL_FLAG_M (BIT(0))
#define ASSIST_DEBUG_LOG_MEM_FULL_FLAG_V 0x1
#define ASSIST_DEBUG_LOG_MEM_FULL_FLAG_S 0
#define ASSIST_DEBUG_C0RE_0_LASTPC_BEFORE_EXCEPTION_REG (DR_REG_ASSIST_DEBUG_BASE + 0x094)
/* ASSIST_DEBUG_CORE_0_LASTPC_BEFORE_EXC : RO ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_LASTPC_BEFORE_EXC 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_LASTPC_BEFORE_EXC_M ((ASSIST_DEBUG_CORE_0_LASTPC_BEFORE_EXC_V)<<(ASSIST_DEBUG_CORE_0_LASTPC_BEFORE_EXC_S))
#define ASSIST_DEBUG_CORE_0_LASTPC_BEFORE_EXC_V 0xFFFFFFFF
#define ASSIST_DEBUG_CORE_0_LASTPC_BEFORE_EXC_S 0
#define ASSIST_DEBUG_C0RE_0_DEBUG_MODE_REG (DR_REG_ASSIST_DEBUG_BASE + 0x098)
/* ASSIST_DEBUG_CORE_0_DEBUG_MODULE_ACTIVE : RO ;bitpos:[1] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_DEBUG_MODULE_ACTIVE (BIT(1))
#define ASSIST_DEBUG_CORE_0_DEBUG_MODULE_ACTIVE_M (BIT(1))
#define ASSIST_DEBUG_CORE_0_DEBUG_MODULE_ACTIVE_V 0x1
#define ASSIST_DEBUG_CORE_0_DEBUG_MODULE_ACTIVE_S 1
/* ASSIST_DEBUG_CORE_0_DEBUG_MODE : RO ;bitpos:[0] ;default: 1'b0 ; */
/*description: */
#define ASSIST_DEBUG_CORE_0_DEBUG_MODE (BIT(0))
#define ASSIST_DEBUG_CORE_0_DEBUG_MODE_M (BIT(0))
#define ASSIST_DEBUG_CORE_0_DEBUG_MODE_V 0x1
#define ASSIST_DEBUG_CORE_0_DEBUG_MODE_S 0
#define ASSIST_DEBUG_DATE_REG (DR_REG_ASSIST_DEBUG_BASE + 0x1FC)
/* ASSIST_DEBUG_DATE : R/W ;bitpos:[27:0] ;default: 28'h2008010 ; */
/*description: */
#define ASSIST_DEBUG_DATE 0x0FFFFFFF
#define ASSIST_DEBUG_DATE_M ((ASSIST_DEBUG_DATE_V)<<(ASSIST_DEBUG_DATE_S))
#define ASSIST_DEBUG_DATE_V 0xFFFFFFF
#define ASSIST_DEBUG_DATE_S 0
#ifdef __cplusplus
}
#endif
#endif /*_SOC_ASSIST_DEBUG_REG_H_ */

View File

@ -0,0 +1,37 @@
// Copyright 2010-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
/* Some of the baseband control registers.
* PU/PD fields defined here are used in sleep related functions.
*/
#define BBPD_CTRL (DR_REG_BB_BASE + 0x0054)
#define BB_FFT_FORCE_PU (BIT(3))
#define BB_FFT_FORCE_PU_M (BIT(3))
#define BB_FFT_FORCE_PU_V 1
#define BB_FFT_FORCE_PU_S 3
#define BB_FFT_FORCE_PD (BIT(2))
#define BB_FFT_FORCE_PD_M (BIT(2))
#define BB_FFT_FORCE_PD_V 1
#define BB_FFT_FORCE_PD_S 2
#define BB_DC_EST_FORCE_PU (BIT(1))
#define BB_DC_EST_FORCE_PU_M (BIT(1))
#define BB_DC_EST_FORCE_PU_V 1
#define BB_DC_EST_FORCE_PU_S 1
#define BB_DC_EST_FORCE_PD (BIT(0))
#define BB_DC_EST_FORCE_PD_M (BIT(0))
#define BB_DC_EST_FORCE_PD_V 1
#define BB_DC_EST_FORCE_PD_S 0

View File

@ -0,0 +1,101 @@
// 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.
#ifndef _SOC_BOOT_MODE_H_
#define _SOC_BOOT_MODE_H_
#include "soc.h"
/*SPI Boot*/
#define IS_1XXX(v) (((v)&0x08)==0x08)
/*Download Boot, SPI(or SDIO_V2)/UART0*/
#define IS_00XX(v) (((v)&0x0c)==0x00)
/*Download Boot, SDIO/UART0/UART1,FEI_FEO V2*/
#define IS_0000(v) (((v)&0x0f)==0x00)
/*Download Boot, SDIO/UART0/UART1,FEI_REO V2*/
#define IS_0001(v) (((v)&0x0f)==0x01)
/*Download Boot, SDIO/UART0/UART1,REI_FEO V2*/
#define IS_0010(v) (((v)&0x0f)==0x02)
/*Download Boot, SDIO/UART0/UART1,REI_REO V2*/
#define IS_0011(v) (((v)&0x0f)==0x03)
/*legacy SPI Boot*/
#define IS_0100(v) (((v)&0x0f)==0x04)
/*ATE/ANALOG Mode*/
#define IS_0101(v) (((v)&0x0f)==0x05)
/*SPI(or SDIO_V1) download Mode*/
#define IS_0110(v) (((v)&0x0f)==0x06)
/*Diagnostic Mode+UART0 download Mode*/
#define IS_0111(v) (((v)&0x0f)==0x07)
#define BOOT_MODE_GET() (GPIO_REG_READ(GPIO_STRAP_REG))
/*do not include download mode*/
#define ETS_IS_UART_BOOT() IS_0111(BOOT_MODE_GET())
/*all spi boot including spi/legacy*/
#define ETS_IS_FLASH_BOOT() (IS_1XXX(BOOT_MODE_GET()) || IS_0100(BOOT_MODE_GET()))
/*all faster spi boot including spi*/
#define ETS_IS_FAST_FLASH_BOOT() IS_1XXX(BOOT_MODE_GET())
#if SUPPORT_SDIO_DOWNLOAD
/*all sdio V2 of failing edge input, failing edge output*/
#define ETS_IS_SDIO_FEI_FEO_V2_BOOT() IS_0000(BOOT_MODE_GET())
/*all sdio V2 of failing edge input, raising edge output*/
#define ETS_IS_SDIO_FEI_REO_V2_BOOT() IS_0001(BOOT_MODE_GET())
/*all sdio V2 of raising edge input, failing edge output*/
#define ETS_IS_SDIO_REI_FEO_V2_BOOT() IS_0010(BOOT_MODE_GET())
/*all sdio V2 of raising edge input, raising edge output*/
#define ETS_IS_SDIO_REI_REO_V2_BOOT() IS_0011(BOOT_MODE_GET())
/*all sdio V1 of raising edge input, failing edge output*/
#define ETS_IS_SDIO_REI_FEO_V1_BOOT() IS_0110(BOOT_MODE_GET())
/*do not include joint download mode*/
#define ETS_IS_SDIO_BOOT() IS_0110(BOOT_MODE_GET())
#else
/*do not include joint download mode*/
#define ETS_IS_SPI_DOWNLOAD_BOOT() IS_0110(BOOT_MODE_GET())
#endif
/*joint download boot*/
#define ETS_IS_JOINT_DOWNLOAD_BOOT() IS_00XX(BOOT_MODE_GET())
/*ATE mode*/
#define ETS_IS_ATE_BOOT() IS_0101(BOOT_MODE_GET())
/*used by ETS_IS_SDIO_UART_BOOT*/
#define SEL_NO_BOOT 0
#define SEL_SDIO_BOOT BIT0
#define SEL_UART_BOOT BIT1
#define SEL_SPI_SLAVE_BOOT BIT2
#endif /* _SOC_BOOT_MODE_H_ */

View File

@ -0,0 +1,100 @@
// 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.
#ifndef _CACHE_MEMORY_H_
#define _CACHE_MEMORY_H_
#ifdef __cplusplus
extern "C" {
#endif
/*IRAM0 is connected with Cache IBUS0*/
#define IRAM0_ADDRESS_LOW 0x40000000
#define IRAM0_ADDRESS_HIGH 0x44000000
#define IRAM0_CACHE_ADDRESS_LOW 0x42000000
#define IRAM0_CACHE_ADDRESS_HIGH 0x42800000
/*DRAM0 is connected with Cache DBUS0*/
#define DRAM0_ADDRESS_LOW 0x3C000000
#define DRAM0_ADDRESS_HIGH 0x40000000
#define DRAM0_CACHE_ADDRESS_LOW 0x3C000000
#define DRAM0_CACHE_ADDRESS_HIGH 0x3C800000
#define DRAM0_CACHE_OPERATION_HIGH DRAM0_CACHE_ADDRESS_HIGH
#define ESP_CACHE_TEMP_ADDR 0x3C000000
#define BUS_SIZE(bus_name) (bus_name##_ADDRESS_HIGH - bus_name##_ADDRESS_LOW)
#define ADDRESS_IN_BUS(bus_name, vaddr) ((vaddr) >= bus_name##_ADDRESS_LOW && (vaddr) < bus_name##_ADDRESS_HIGH)
#define ADDRESS_IN_IRAM0(vaddr) ADDRESS_IN_BUS(IRAM0, vaddr)
#define ADDRESS_IN_IRAM0_CACHE(vaddr) ADDRESS_IN_BUS(IRAM0_CACHE, vaddr)
#define ADDRESS_IN_DRAM0(vaddr) ADDRESS_IN_BUS(DRAM0, vaddr)
#define ADDRESS_IN_DRAM0_CACHE(vaddr) ADDRESS_IN_BUS(DRAM0_CACHE, vaddr)
#define BUS_IRAM0_CACHE_SIZE BUS_SIZE(IRAM0_CACHE)
#define BUS_DRAM0_CACHE_SIZE BUS_SIZE(DRAM0_CACHE)
#define CACHE_IBUS 0
#define CACHE_IBUS_MMU_START 0
#define CACHE_IBUS_MMU_END 0x200
#define CACHE_DBUS 1
#define CACHE_DBUS_MMU_START 0
#define CACHE_DBUS_MMU_END 0x200
#define CACHE_IROM_MMU_START 0
#define CACHE_IROM_MMU_END Cache_Get_IROM_MMU_End()
#define CACHE_IROM_MMU_SIZE (CACHE_IROM_MMU_END - CACHE_IROM_MMU_START)
#define CACHE_DROM_MMU_START CACHE_IROM_MMU_END
#define CACHE_DROM_MMU_END Cache_Get_DROM_MMU_End()
#define CACHE_DROM_MMU_SIZE (CACHE_DROM_MMU_END - CACHE_DROM_MMU_START)
#define CACHE_DROM_MMU_MAX_END 0x200
#define ICACHE_MMU_SIZE 0x200
#define DCACHE_MMU_SIZE 0x200
#define MMU_BUS_START(i) 0
#define MMU_BUS_SIZE(i) 0x200
#define MMU_INVALID BIT(8)
#define MMU_TYPE 0
#define MMU_ACCESS_FLASH 0
#define CACHE_MAX_SYNC_NUM 0x400000
#define CACHE_MAX_LOCK_NUM 0x8000
#define FLASH_MMU_TABLE ((volatile uint32_t*) DR_REG_MMU_TABLE)
#define FLASH_MMU_TABLE_SIZE (ICACHE_MMU_SIZE/sizeof(uint32_t))
#define MMU_TABLE_INVALID_VAL 0x100
#define FLASH_MMU_TABLE_INVALID_VAL DPORT_MMU_TABLE_INVALID_VAL
#define MMU_ADDRESS_MASK 0xff
#define MMU_PAGE_SIZE 0x10000
#define INVALID_PHY_PAGE 0xffff
#define BUS_ADDR_SIZE 0x800000
#define BUS_ADDR_MASK (BUS_ADDR_SIZE - 1)
#define CACHE_ICACHE_LOW_SHIFT 0
#define CACHE_ICACHE_HIGH_SHIFT 2
#define CACHE_DCACHE_LOW_SHIFT 4
#define CACHE_DCACHE_HIGH_SHIFT 6
#define CACHE_MEMORY_IBANK0_ADDR 0x4037c000
#ifdef __cplusplus
}
#endif
#endif /*_CACHE_MEMORY_H_ */

View File

@ -0,0 +1,26 @@
// Copyright 2010-2016 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.
#ifndef _SOC_CLKOUT_CHANNEL_H
#define _SOC_CLKOUT_CHANNEL_H
//CLKOUT channels
#define CLKOUT_GPIO20_DIRECT_CHANNEL CLKOUT_CHANNEL_1
#define CLKOUT_CHANNEL_1_DIRECT_GPIO_NUM 20
#define CLKOUT_GPIO19_DIRECT_CHANNEL CLKOUT_CHANNEL_2
#define CLKOUT_CHANNEL_2_DIRECT_GPIO_NUM 19
#define CLKOUT_GPIO18_DIRECT_CHANNEL CLKOUT_CHANNEL_3
#define CLKOUT_CHANNEL_3_DIRECT_GPIO_NUM 18
#endif

View File

@ -0,0 +1,111 @@
// 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.
#ifndef _DPORT_ACCESS_H_
#define _DPORT_ACCESS_H_
#include <stdint.h>
#include "esp_attr.h"
#include "esp_attr.h"
#include "esp32c3/dport_access.h"
#include "soc.h"
#include "uart_reg.h"
#ifdef __cplusplus
extern "C" {
#endif
// Target does not have DPORT bus, so these macros are all same as the non-DPORT versions
// _DPORT_REG_WRITE & DPORT_REG_WRITE are equivalent.
#define _DPORT_REG_READ(_r) (*(volatile uint32_t *)(_r))
#define _DPORT_REG_WRITE(_r, _v) (*(volatile uint32_t *)(_r)) = (_v)
// Write value to DPORT register (does not require protecting)
#define DPORT_REG_WRITE(_r, _v) _DPORT_REG_WRITE((_r), (_v))
#define DPORT_REG_READ(_r) _DPORT_REG_READ(_r)
#define DPORT_SEQUENCE_REG_READ(_r) _DPORT_REG_READ(_r)
//get bit or get bits from register
#define DPORT_REG_GET_BIT(_r, _b) (DPORT_REG_READ(_r) & (_b))
//set bit or set bits to register
#define DPORT_REG_SET_BIT(_r, _b) DPORT_REG_WRITE((_r), (DPORT_REG_READ(_r)|(_b)))
//clear bit or clear bits of register
#define DPORT_REG_CLR_BIT(_r, _b) DPORT_REG_WRITE((_r), (DPORT_REG_READ(_r) & (~(_b))))
//set bits of register controlled by mask
#define DPORT_REG_SET_BITS(_r, _b, _m) DPORT_REG_WRITE((_r), ((DPORT_REG_READ(_r) & (~(_m))) | ((_b) & (_m))))
//get field from register, uses field _S & _V to determine mask
#define DPORT_REG_GET_FIELD(_r, _f) ((DPORT_REG_READ(_r) >> (_f##_S)) & (_f##_V))
//set field to register, used when _f is not left shifted by _f##_S
#define DPORT_REG_SET_FIELD(_r, _f, _v) DPORT_REG_WRITE((_r), ((DPORT_REG_READ(_r) & (~((_f##_V) << (_f##_S))))|(((_v) & (_f##_V))<<(_f##_S))))
//get field value from a variable, used when _f is not left shifted by _f##_S
#define DPORT_VALUE_GET_FIELD(_r, _f) (((_r) >> (_f##_S)) & (_f))
//get field value from a variable, used when _f is left shifted by _f##_S
#define DPORT_VALUE_GET_FIELD2(_r, _f) (((_r) & (_f))>> (_f##_S))
//set field value to a variable, used when _f is not left shifted by _f##_S
#define DPORT_VALUE_SET_FIELD(_r, _f, _v) ((_r)=(((_r) & ~((_f) << (_f##_S)))|((_v)<<(_f##_S))))
//set field value to a variable, used when _f is left shifted by _f##_S
#define DPORT_VALUE_SET_FIELD2(_r, _f, _v) ((_r)=(((_r) & ~(_f))|((_v)<<(_f##_S))))
//generate a value from a field value, used when _f is not left shifted by _f##_S
#define DPORT_FIELD_TO_VALUE(_f, _v) (((_v)&(_f))<<_f##_S)
//generate a value from a field value, used when _f is left shifted by _f##_S
#define DPORT_FIELD_TO_VALUE2(_f, _v) (((_v)<<_f##_S) & (_f))
//Register read macros with an underscore prefix access DPORT memory directly. In IDF apps, use the non-underscore versions to be SMP-safe.
#define _DPORT_READ_PERI_REG(addr) (*((volatile uint32_t *)(addr)))
#define _DPORT_WRITE_PERI_REG(addr, val) (*((volatile uint32_t *)(addr))) = (uint32_t)(val)
#define _DPORT_REG_SET_BIT(_r, _b) _DPORT_REG_WRITE((_r), (_DPORT_REG_READ(_r)|(_b)))
#define _DPORT_REG_CLR_BIT(_r, _b) _DPORT_REG_WRITE((_r), (_DPORT_REG_READ(_r) & (~(_b))))
#define DPORT_READ_PERI_REG(addr) _DPORT_READ_PERI_REG(addr)
//write value to register
#define DPORT_WRITE_PERI_REG(addr, val) _DPORT_WRITE_PERI_REG((addr), (val))
//clear bits of register controlled by mask
#define DPORT_CLEAR_PERI_REG_MASK(reg, mask) DPORT_WRITE_PERI_REG((reg), (DPORT_READ_PERI_REG(reg)&(~(mask))))
//set bits of register controlled by mask
#define DPORT_SET_PERI_REG_MASK(reg, mask) DPORT_WRITE_PERI_REG((reg), (DPORT_READ_PERI_REG(reg)|(mask)))
//get bits of register controlled by mask
#define DPORT_GET_PERI_REG_MASK(reg, mask) (DPORT_READ_PERI_REG(reg) & (mask))
//get bits of register controlled by highest bit and lowest bit
#define DPORT_GET_PERI_REG_BITS(reg, hipos,lowpos) ((DPORT_READ_PERI_REG(reg)>>(lowpos))&((1<<((hipos)-(lowpos)+1))-1))
//set bits of register controlled by mask and shift
#define DPORT_SET_PERI_REG_BITS(reg,bit_map,value,shift) DPORT_WRITE_PERI_REG((reg), ((DPORT_READ_PERI_REG(reg)&(~((bit_map)<<(shift))))|(((value) & bit_map)<<(shift))))
//get field of register
#define DPORT_GET_PERI_REG_BITS2(reg, mask,shift) ((DPORT_READ_PERI_REG(reg)>>(shift))&(mask))
//}}
#ifdef __cplusplus
}
#endif
#endif /* _DPORT_ACCESS_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,514 @@
// 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.
#ifndef _SOC_EFUSE_STRUCT_H_
#define _SOC_EFUSE_STRUCT_H_
#ifdef __cplusplus
extern "C" {
#endif
typedef volatile struct {
uint32_t pgm_data0; /*Register 0 that stores data to be programmed.*/
union {
struct {
uint32_t rd_dis: 7; /*Set this bit to disable reading from BlOCK4-10.*/
uint32_t dis_rtc_ram_boot: 1; /*Set this bit to disable boot from RTC RAM.*/
uint32_t dis_icache: 1; /*Set this bit to disable Icache.*/
uint32_t dis_usb_jtag: 1; /*Set this bit to disable function of usb switch to jtag in module of usb device.*/
uint32_t dis_download_icache: 1; /*Set this bit to disable Icache in download mode (boot_mode[3:0] is 0 1 2 3 6 7).*/
uint32_t dis_usb_device: 1; /*Set this bit to disable usb device.*/
uint32_t dis_force_download: 1; /*Set this bit to disable the function that forces chip into download mode.*/
uint32_t dis_usb: 1; /*Set this bit to disable USB function.*/
uint32_t dis_can: 1; /*Set this bit to disable CAN function.*/
uint32_t jtag_sel_enable: 1; /*Set this bit to enable selection between usb_to_jtag and pad_to_jtag through strapping gpio10 when both reg_dis_usb_jtag and reg_dis_pad_jtag are equal to 0.*/
uint32_t soft_dis_jtag: 3; /*Set these bits to disable JTAG in the soft way (odd number 1 means disable ). JTAG can be enabled in HMAC module.*/
uint32_t dis_pad_jtag: 1; /*Set this bit to disable JTAG in the hard way. JTAG is disabled permanently.*/
uint32_t dis_download_manual_encrypt: 1; /*Set this bit to disable flash encryption when in download boot modes.*/
uint32_t usb_drefh: 2; /*Controls single-end input threshold vrefh 1.76 V to 2 V with step of 80 mV stored in eFuse.*/
uint32_t usb_drefl: 2; /*Controls single-end input threshold vrefl 0.8 V to 1.04 V with step of 80 mV stored in eFuse.*/
uint32_t usb_exchg_pins: 1; /*Set this bit to exchange USB D+ and D- pins.*/
uint32_t vdd_spi_as_gpio: 1; /*Set this bit to vdd spi pin function as gpio.*/
uint32_t btlc_gpio_enable: 2; /*Enable btlc gpio.*/
uint32_t powerglitch_en: 1; /*Set this bit to enable power glitch function.*/
uint32_t power_glitch_dsense: 2; /*Sample delay configuration of power glitch.*/
};
uint32_t val;
} pgm_data1;
union {
struct {
uint32_t rpt4_reserved2: 16; /*Reserved (used for four backups method).*/
uint32_t wat_delay_sel: 2; /*Selects RTC watchdog timeout threshold in unit of slow clock cycle. 0: 40000. 1: 80000. 2: 160000. 3:320000.*/
uint32_t spi_boot_crypt_cnt: 3; /*Set this bit to enable SPI boot encrypt/decrypt. Odd number of 1: enable. even number of 1: disable.*/
uint32_t secure_boot_key_revoke0: 1; /*Set this bit to enable revoking first secure boot key.*/
uint32_t secure_boot_key_revoke1: 1; /*Set this bit to enable revoking second secure boot key.*/
uint32_t secure_boot_key_revoke2: 1; /*Set this bit to enable revoking third secure boot key.*/
uint32_t key_purpose_0: 4; /*Purpose of Key0.*/
uint32_t key_purpose_1: 4; /*Purpose of Key1.*/
};
uint32_t val;
} pgm_data2;
union {
struct {
uint32_t key_purpose_2: 4; /*Purpose of Key2.*/
uint32_t key_purpose_3: 4; /*Purpose of Key3.*/
uint32_t key_purpose_4: 4; /*Purpose of Key4.*/
uint32_t key_purpose_5: 4; /*Purpose of Key5.*/
uint32_t rpt4_reserved3: 4; /*Reserved (used for four backups method).*/
uint32_t secure_boot_en: 1; /*Set this bit to enable secure boot.*/
uint32_t secure_boot_aggressive_revoke: 1; /*Set this bit to enable revoking aggressive secure boot.*/
uint32_t rpt4_reserved0: 6; /*Reserved (used for four backups method).*/
uint32_t flash_tpuw: 4; /*Configures flash waiting time after power-up in unit of ms. If the value is less than 15 the waiting time is the configurable value*/
};
uint32_t val;
} pgm_data3;
union {
struct {
uint32_t dis_download_mode: 1; /*Set this bit to disable download mode (boot_mode[3:0] = 0 1 2 3 6 7).*/
uint32_t dis_legacy_spi_boot: 1; /*Set this bit to disable Legacy SPI boot mode (boot_mode[3:0] = 4).*/
uint32_t uart_print_channel: 1; /*Selectes the default UART print channel. 0: UART0. 1: UART1.*/
uint32_t flash_ecc_mode: 1; /*Set ECC mode in ROM 0: ROM would Enable Flash ECC 16to18 byte mode. 1:ROM would use 16to17 byte mode.*/
uint32_t dis_usb_download_mode: 1; /*Set this bit to disable UART download mode through USB.*/
uint32_t enable_security_download: 1; /*Set this bit to enable secure UART download mode.*/
uint32_t uart_print_control: 2; /*Set the default UARTboot message output mode. 00: Enabled. 01: Enabled when GPIO8 is low at reset. 10: Enabled when GPIO8 is high at reset. 11:disabled.*/
uint32_t pin_power_selection: 1; /*GPIO33-GPIO37 power supply selection in ROM code. 0: VDD3P3_CPU. 1: VDD_SPI.*/
uint32_t flash_type: 1; /*Set the maximum lines of SPI flash. 0: four lines. 1: eight lines.*/
uint32_t flash_page_size: 2; /*Set Flash page size.*/
uint32_t flash_ecc_en: 1; /*Set 1 to enable ECC for flash boot.*/
uint32_t force_send_resume: 1; /*Set this bit to force ROM code to send a resume command during SPI boot.*/
uint32_t secure_version: 16; /*Secure version (used by ESP-IDF anti-rollback feature).*/
uint32_t rpt4_reserved1: 2; /*Reserved (used for four backups method).*/
};
uint32_t val;
} pgm_data4;
union {
struct {
uint32_t rpt4_reserved4:24; /*Reserved (used for four backups method).*/
uint32_t reserved24: 8; /*Reserved.*/
};
uint32_t val;
} pgm_data5;
uint32_t pgm_data6; /*Register 6 that stores data to be programmed.*/
uint32_t pgm_data7; /*Register 7 that stores data to be programmed.*/
uint32_t pgm_check_value0; /*Register 0 that stores the RS code to be programmed.*/
uint32_t pgm_check_value1; /*Register 1 that stores the RS code to be programmed.*/
uint32_t pgm_check_value2; /*Register 2 that stores the RS code to be programmed.*/
uint32_t rd_wr_dis; /*BLOCK0 data register $n.*/
union {
struct {
uint32_t rd_dis: 7; /*The value of RD_DIS.*/
uint32_t dis_rtc_ram_boot: 1; /*The value of DIS_RTC_RAM_BOOT.*/
uint32_t dis_icache: 1; /*The value of DIS_ICACHE.*/
uint32_t dis_usb_jtag: 1; /*The value of DIS_USB_JTAG.*/
uint32_t dis_download_icache: 1; /*The value of DIS_DOWNLOAD_ICACHE.*/
uint32_t dis_usb_device: 1; /*The value of DIS_USB_DEVICE.*/
uint32_t dis_force_download: 1; /*The value of DIS_FORCE_DOWNLOAD.*/
uint32_t dis_usb: 1; /*The value of DIS_USB.*/
uint32_t dis_can: 1; /*The value of DIS_CAN.*/
uint32_t jtag_sel_enable: 1; /*The value of JTAG_SEL_ENABLE.*/
uint32_t soft_dis_jtag: 3; /*The value of SOFT_DIS_JTAG.*/
uint32_t dis_pad_jtag: 1; /*The value of DIS_PAD_JTAG.*/
uint32_t dis_download_manual_encrypt: 1; /*The value of DIS_DOWNLOAD_MANUAL_ENCRYPT.*/
uint32_t usb_drefh: 2; /*The value of USB_DREFH.*/
uint32_t usb_drefl: 2; /*The value of USB_DREFL.*/
uint32_t usb_exchg_pins: 1; /*The value of USB_EXCHG_PINS.*/
uint32_t vdd_spi_as_gpio: 1; /*The value of VDD_SPI_AS_GPIO.*/
uint32_t btlc_gpio_enable: 2; /*The value of BTLC_GPIO_ENABLE.*/
uint32_t powerglitch_en: 1; /*The value of POWERGLITCH_EN.*/
uint32_t power_glitch_dsense: 2; /*The value of POWER_GLITCH_DSENSE.*/
};
uint32_t val;
} rd_repeat_data0;
union {
struct {
uint32_t rpt4_reserved2: 16; /*Reserved.*/
uint32_t wdt_delay_sel: 2; /*The value of WDT_DELAY_SEL.*/
uint32_t spi_boot_crypt_cnt: 3; /*The value of SPI_BOOT_CRYPT_CNT.*/
uint32_t secure_boot_key_revoke0: 1; /*The value of SECURE_BOOT_KEY_REVOKE0.*/
uint32_t secure_boot_key_revoke1: 1; /*The value of SECURE_BOOT_KEY_REVOKE1.*/
uint32_t secure_boot_key_revoke2: 1; /*The value of SECURE_BOOT_KEY_REVOKE2.*/
uint32_t key_purpose_0: 4; /*The value of KEY_PURPOSE_0.*/
uint32_t key_purpose_1: 4; /*The value of KEY_PURPOSE_1.*/
};
uint32_t val;
} rd_repeat_data1;
union {
struct {
uint32_t key_purpose_2: 4; /*The value of KEY_PURPOSE_2.*/
uint32_t key_purpose_3: 4; /*The value of KEY_PURPOSE_3.*/
uint32_t key_purpose_4: 4; /*The value of KEY_PURPOSE_4.*/
uint32_t key_purpose_5: 4; /*The value of KEY_PURPOSE_5.*/
uint32_t rpt4_reserved3: 4; /*Reserved.*/
uint32_t secure_boot_en: 1; /*The value of SECURE_BOOT_EN.*/
uint32_t secure_boot_aggressive_revoke: 1; /*The value of SECURE_BOOT_AGGRESSIVE_REVOKE.*/
uint32_t rpt4_reserved0: 6; /*Reserved.*/
uint32_t flash_tpuw: 4; /*The value of FLASH_TPUW.*/
};
uint32_t val;
} rd_repeat_data2;
union {
struct {
uint32_t dis_download_mode: 1; /*The value of DIS_DOWNLOAD_MODE.*/
uint32_t dis_legacy_spi_boot: 1; /*The value of DIS_LEGACY_SPI_BOOT.*/
uint32_t uart_print_channel: 1; /*The value of UART_PRINT_CHANNEL.*/
uint32_t flash_ecc_mode: 1; /*The value of FLASH_ECC_MODE.*/
uint32_t dis_usb_download_mode: 1; /*The value of DIS_USB_DOWNLOAD_MODE.*/
uint32_t enable_security_download: 1; /*The value of ENABLE_SECURITY_DOWNLOAD.*/
uint32_t uart_print_control: 2; /*The value of UART_PRINT_CONTROL.*/
uint32_t pin_power_selection: 1; /*The value of PIN_POWER_SELECTION.*/
uint32_t flash_type: 1; /*The value of FLASH_TYPE.*/
uint32_t flash_page_size: 2; /*The value of FLASH_PAGE_SIZE.*/
uint32_t flash_ecc_en: 1; /*The value of FLASH_ECC_EN.*/
uint32_t force_send_resume: 1; /*The value of FORCE_SEND_RESUME.*/
uint32_t secure_version: 16; /*The value of SECURE_VERSION.*/
uint32_t rpt4_reserved1: 2; /*Reserved.*/
};
uint32_t val;
} rd_repeat_data3;
union {
struct {
uint32_t rpt4_reserved4:24; /*Reserved.*/
uint32_t reserved24: 8; /*Reserved.*/
};
uint32_t val;
} rd_repeat_data4;
uint32_t rd_mac_spi_sys_0; /*BLOCK1 data register $n.*/
union {
struct {
uint32_t mac_1: 16; /*Stores the high 16 bits of MAC address.*/
uint32_t spi_pad_conf_0:16; /*Stores the zeroth part of SPI_PAD_CONF.*/
};
uint32_t val;
} rd_mac_spi_sys_1;
uint32_t rd_mac_spi_sys_2; /*BLOCK1 data register $n.*/
union {
struct {
uint32_t spi_pad_conf_2: 18; /*Stores the second part of SPI_PAD_CONF.*/
uint32_t sys_data_part0_0:14; /*Stores the fist 14 bits of the zeroth part of system data.*/
};
uint32_t val;
} rd_mac_spi_sys_3;
uint32_t rd_mac_spi_sys_4; /*BLOCK1 data register $n.*/
uint32_t rd_mac_spi_sys_5; /*BLOCK1 data register $n.*/
uint32_t rd_sys_part1_data0; /*Register $n of BLOCK2 (system).*/
uint32_t rd_sys_part1_data1; /*Register $n of BLOCK2 (system).*/
uint32_t rd_sys_part1_data2; /*Register $n of BLOCK2 (system).*/
uint32_t rd_sys_part1_data3; /*Register $n of BLOCK2 (system).*/
uint32_t rd_sys_part1_data4; /*Register $n of BLOCK2 (system).*/
uint32_t rd_sys_part1_data5; /*Register $n of BLOCK2 (system).*/
uint32_t rd_sys_part1_data6; /*Register $n of BLOCK2 (system).*/
uint32_t rd_sys_part1_data7; /*Register $n of BLOCK2 (system).*/
uint32_t rd_usr_data0; /*Register $n of BLOCK3 (user).*/
uint32_t rd_usr_data1; /*Register $n of BLOCK3 (user).*/
uint32_t rd_usr_data2; /*Register $n of BLOCK3 (user).*/
uint32_t rd_usr_data3; /*Register $n of BLOCK3 (user).*/
uint32_t rd_usr_data4; /*Register $n of BLOCK3 (user).*/
uint32_t rd_usr_data5; /*Register $n of BLOCK3 (user).*/
uint32_t rd_usr_data6; /*Register $n of BLOCK3 (user).*/
uint32_t rd_usr_data7; /*Register $n of BLOCK3 (user).*/
uint32_t rd_key0_data0; /*Register $n of BLOCK4 (KEY0).*/
uint32_t rd_key0_data1; /*Register $n of BLOCK4 (KEY0).*/
uint32_t rd_key0_data2; /*Register $n of BLOCK4 (KEY0).*/
uint32_t rd_key0_data3; /*Register $n of BLOCK4 (KEY0).*/
uint32_t rd_key0_data4; /*Register $n of BLOCK4 (KEY0).*/
uint32_t rd_key0_data5; /*Register $n of BLOCK4 (KEY0).*/
uint32_t rd_key0_data6; /*Register $n of BLOCK4 (KEY0).*/
uint32_t rd_key0_data7; /*Register $n of BLOCK4 (KEY0).*/
uint32_t rd_key1_data0; /*Register $n of BLOCK5 (KEY1).*/
uint32_t rd_key1_data1; /*Register $n of BLOCK5 (KEY1).*/
uint32_t rd_key1_data2; /*Register $n of BLOCK5 (KEY1).*/
uint32_t rd_key1_data3; /*Register $n of BLOCK5 (KEY1).*/
uint32_t rd_key1_data4; /*Register $n of BLOCK5 (KEY1).*/
uint32_t rd_key1_data5; /*Register $n of BLOCK5 (KEY1).*/
uint32_t rd_key1_data6; /*Register $n of BLOCK5 (KEY1).*/
uint32_t rd_key1_data7; /*Register $n of BLOCK5 (KEY1).*/
uint32_t rd_key2_data0; /*Register $n of BLOCK6 (KEY2).*/
uint32_t rd_key2_data1; /*Register $n of BLOCK6 (KEY2).*/
uint32_t rd_key2_data2; /*Register $n of BLOCK6 (KEY2).*/
uint32_t rd_key2_data3; /*Register $n of BLOCK6 (KEY2).*/
uint32_t rd_key2_data4; /*Register $n of BLOCK6 (KEY2).*/
uint32_t rd_key2_data5; /*Register $n of BLOCK6 (KEY2).*/
uint32_t rd_key2_data6; /*Register $n of BLOCK6 (KEY2).*/
uint32_t rd_key2_data7; /*Register $n of BLOCK6 (KEY2).*/
uint32_t rd_key3_data0; /*Register $n of BLOCK7 (KEY3).*/
uint32_t rd_key3_data1; /*Register $n of BLOCK7 (KEY3).*/
uint32_t rd_key3_data2; /*Register $n of BLOCK7 (KEY3).*/
uint32_t rd_key3_data3; /*Register $n of BLOCK7 (KEY3).*/
uint32_t rd_key3_data4; /*Register $n of BLOCK7 (KEY3).*/
uint32_t rd_key3_data5; /*Register $n of BLOCK7 (KEY3).*/
uint32_t rd_key3_data6; /*Register $n of BLOCK7 (KEY3).*/
uint32_t rd_key3_data7; /*Register $n of BLOCK7 (KEY3).*/
uint32_t rd_key4_data0; /*Register $n of BLOCK8 (KEY4).*/
uint32_t rd_key4_data1; /*Register $n of BLOCK8 (KEY4).*/
uint32_t rd_key4_data2; /*Register $n of BLOCK8 (KEY4).*/
uint32_t rd_key4_data3; /*Register $n of BLOCK8 (KEY4).*/
uint32_t rd_key4_data4; /*Register $n of BLOCK8 (KEY4).*/
uint32_t rd_key4_data5; /*Register $n of BLOCK8 (KEY4).*/
uint32_t rd_key4_data6; /*Register $n of BLOCK8 (KEY4).*/
uint32_t rd_key4_data7; /*Register $n of BLOCK8 (KEY4).*/
uint32_t rd_key5_data0; /*Register $n of BLOCK9 (KEY5).*/
uint32_t rd_key5_data1; /*Register $n of BLOCK9 (KEY5).*/
uint32_t rd_key5_data2; /*Register $n of BLOCK9 (KEY5).*/
uint32_t rd_key5_data3; /*Register $n of BLOCK9 (KEY5).*/
uint32_t rd_key5_data4; /*Register $n of BLOCK9 (KEY5).*/
uint32_t rd_key5_data5; /*Register $n of BLOCK9 (KEY5).*/
uint32_t rd_key5_data6; /*Register $n of BLOCK9 (KEY5).*/
uint32_t rd_key5_data7; /*Register $n of BLOCK9 (KEY5).*/
uint32_t rd_sys_part2_data0; /*Register $n of BLOCK10 (system).*/
uint32_t rd_sys_part2_data1; /*Register $n of BLOCK9 (KEY5).*/
uint32_t rd_sys_part2_data2; /*Register $n of BLOCK10 (system).*/
uint32_t rd_sys_part2_data3; /*Register $n of BLOCK10 (system).*/
uint32_t rd_sys_part2_data4; /*Register $n of BLOCK10 (system).*/
uint32_t rd_sys_part2_data5; /*Register $n of BLOCK10 (system).*/
uint32_t rd_sys_part2_data6; /*Register $n of BLOCK10 (system).*/
uint32_t rd_sys_part2_data7; /*Register $n of BLOCK10 (system).*/
union {
struct {
uint32_t rd_dis_err: 7; /*If any bit in RD_DIS is 1 then it indicates a programming error.*/
uint32_t dis_rtc_ram_boot_err: 1; /*If DIS_RTC_RAM_BOOT is 1 then it indicates a programming error.*/
uint32_t dis_icache_err: 1; /*If DIS_ICACHE is 1 then it indicates a programming error.*/
uint32_t dis_usb_jtag_err: 1; /*If DIS_USB_JTAG is 1 then it indicates a programming error.*/
uint32_t dis_download_icache: 1; /*If DIS_DOWNLOAD_ICACHE is 1 then it indicates a programming error.*/
uint32_t dis_usb_device_err: 1; /*If DIS_USB_DEVICE is 1 then it indicates a programming error.*/
uint32_t dis_force_download_err: 1; /*If DIS_FORCE_DOWNLOAD is 1 then it indicates a programming error.*/
uint32_t dis_usb_err: 1; /*If DIS_USB is 1 then it indicates a programming error.*/
uint32_t dis_can_err: 1; /*If DIS_CAN is 1 then it indicates a programming error.*/
uint32_t jtag_sel_enable_err: 1; /*If JTAG_SEL_ENABLE is 1 then it indicates a programming error.*/
uint32_t soft_dis_jtag_err: 3; /*If SOFT_DIS_JTAG is 1 then it indicates a programming error.*/
uint32_t dis_pad_jtag_err: 1; /*If DIS_PAD_JTAG is 1 then it indicates a programming error.*/
uint32_t dis_download_manual_encrypt_err: 1; /*If DIS_DOWNLOAD_MANUAL_ENCRYPT is 1 then it indicates a programming error.*/
uint32_t usb_drefh_err: 2; /*If any bit in USB_DREFH is 1 then it indicates a programming error.*/
uint32_t usb_drefl_err: 2; /*If any bit in USB_DREFL is 1 then it indicates a programming error.*/
uint32_t usb_exchg_pins_err: 1; /*If USB_EXCHG_PINS is 1 then it indicates a programming error.*/
uint32_t vdd_spi_as_gpio_err: 1; /*If VDD_SPI_AS_GPIO is 1 then it indicates a programming error.*/
uint32_t btlc_gpio_enable_err: 2; /*If any bit in BTLC_GPIO_ENABLE is 1 then it indicates a programming error.*/
uint32_t powerglitch_en_err: 1; /*If POWERGLITCH_EN is 1 then it indicates a programming error.*/
uint32_t power_glitch_dsense_err: 2; /*If any bit in POWER_GLITCH_DSENSE is 1 then it indicates a programming error.*/
};
uint32_t val;
} rd_repeat_err0;
union {
struct {
uint32_t rpt4_reserved2_err: 16; /*Reserved.*/
uint32_t wdt_delay_sel_err: 2; /*If any bit in WDT_DELAY_SEL is 1 then it indicates a programming error.*/
uint32_t spi_boot_crypt_cnt_err: 3; /*If any bit in SPI_BOOT_CRYPT_CNT is 1 then it indicates a programming error.*/
uint32_t secure_boot_key_revoke0_err: 1; /*If SECURE_BOOT_KEY_REVOKE0 is 1 then it indicates a programming error.*/
uint32_t secure_boot_key_revoke1_err: 1; /*If SECURE_BOOT_KEY_REVOKE1 is 1 then it indicates a programming error.*/
uint32_t secure_boot_key_revoke2_err: 1; /*If SECURE_BOOT_KEY_REVOKE2 is 1 then it indicates a programming error.*/
uint32_t key_purpose_0_err: 4; /*If any bit in KEY_PURPOSE_0 is 1 then it indicates a programming error.*/
uint32_t key_purpose_1_err: 4; /*If any bit in KEY_PURPOSE_1 is 1 then it indicates a programming error.*/
};
uint32_t val;
} rd_repeat_err1;
union {
struct {
uint32_t key_purpose_2_err: 4; /*If any bit in KEY_PURPOSE_2 is 1 then it indicates a programming error.*/
uint32_t key_purpose_3_err: 4; /*If any bit in KEY_PURPOSE_3 is 1 then it indicates a programming error.*/
uint32_t key_purpose_4_err: 4; /*If any bit in KEY_PURPOSE_4 is 1 then it indicates a programming error.*/
uint32_t key_purpose_5_err: 4; /*If any bit in KEY_PURPOSE_5 is 1 then it indicates a programming error.*/
uint32_t rpt4_reserved3_err: 4; /*Reserved.*/
uint32_t secure_boot_en_err: 1; /*If SECURE_BOOT_EN is 1 then it indicates a programming error.*/
uint32_t secure_boot_aggressive_revoke_err: 1; /*If SECURE_BOOT_AGGRESSIVE_REVOKE is 1 then it indicates a programming error.*/
uint32_t rpt4_reserved0_err: 6; /*Reserved.*/
uint32_t flash_tpuw_err: 4; /*If any bit in FLASH_TPUM is 1 then it indicates a programming error.*/
};
uint32_t val;
} rd_repeat_err2;
union {
struct {
uint32_t dis_download_mode_err: 1; /*If DIS_DOWNLOAD_MODE is 1 then it indicates a programming error.*/
uint32_t dis_legacy_spi_boot_err: 1; /*If DIS_LEGACY_SPI_BOOT is 1 then it indicates a programming error.*/
uint32_t uart_print_channel_err: 1; /*If UART_PRINT_CHANNEL is 1 then it indicates a programming error.*/
uint32_t flash_ecc_mode_err: 1; /*If FLASH_ECC_MODE is 1 then it indicates a programming error.*/
uint32_t dis_usb_download_mode_err: 1; /*If DIS_USB_DOWNLOAD_MODE is 1 then it indicates a programming error.*/
uint32_t enable_security_download_err: 1; /*If ENABLE_SECURITY_DOWNLOAD is 1 then it indicates a programming error.*/
uint32_t uart_print_control_err: 2; /*If any bit in UART_PRINT_CONTROL is 1 then it indicates a programming error.*/
uint32_t pin_power_selection_err: 1; /*If PIN_POWER_SELECTION is 1 then it indicates a programming error.*/
uint32_t flash_type_err: 1; /*If FLASH_TYPE is 1 then it indicates a programming error.*/
uint32_t flash_page_size: 2; /*If any bits in FLASH_PAGE_SIZE is 1 then it indicates a programming error.*/
uint32_t flash_ecc_en: 1; /*If FLASH_ECC_EN_ERR is 1 then it indicates a programming error.*/
uint32_t force_send_resume_err: 1; /*If FORCE_SEND_RESUME is 1 then it indicates a programming error.*/
uint32_t secure_version_err: 16; /*If any bit in SECURE_VERSION is 1 then it indicates a programming error.*/
uint32_t rpt4_reserved1_err: 2; /*Reserved.*/
};
uint32_t val;
} rd_repeat_err3;
uint32_t reserved_18c;
union {
struct {
uint32_t rpt4_reserved4_err:24; /*Reserved.*/
uint32_t reserved24: 8; /*Reserved.*/
};
uint32_t val;
} rd_repeat_err4;
uint32_t reserved_194;
uint32_t reserved_198;
uint32_t reserved_19c;
uint32_t reserved_1a0;
uint32_t reserved_1a4;
uint32_t reserved_1a8;
uint32_t reserved_1ac;
uint32_t reserved_1b0;
uint32_t reserved_1b4;
uint32_t reserved_1b8;
uint32_t reserved_1bc;
union {
struct {
uint32_t mac_spi_8m_err_num: 3; /*The value of this signal means the number of error bytes.*/
uint32_t mac_spi_8m_fail: 1; /*0: Means no failure and that the data of MAC_SPI_8M is reliable 1: Means that programming user data failed and the number of error bytes is over 6.*/
uint32_t sys_part1_num: 3; /*The value of this signal means the number of error bytes.*/
uint32_t sys_part1_fail: 1; /*0: Means no failure and that the data of system part1 is reliable 1: Means that programming user data failed and the number of error bytes is over 6.*/
uint32_t usr_data_err_num: 3; /*The value of this signal means the number of error bytes.*/
uint32_t usr_data_fail: 1; /*0: Means no failure and that the user data is reliable 1: Means that programming user data failed and the number of error bytes is over 6.*/
uint32_t key0_err_num: 3; /*The value of this signal means the number of error bytes.*/
uint32_t key0_fail: 1; /*0: Means no failure and that the data of key$n is reliable 1: Means that programming key$n failed and the number of error bytes is over 6.*/
uint32_t key1_err_num: 3; /*The value of this signal means the number of error bytes.*/
uint32_t key1_fail: 1; /*0: Means no failure and that the data of key$n is reliable 1: Means that programming key$n failed and the number of error bytes is over 6.*/
uint32_t key2_err_num: 3; /*The value of this signal means the number of error bytes.*/
uint32_t key2_fail: 1; /*0: Means no failure and that the data of key$n is reliable 1: Means that programming key$n failed and the number of error bytes is over 6.*/
uint32_t key3_err_num: 3; /*The value of this signal means the number of error bytes.*/
uint32_t key3_fail: 1; /*0: Means no failure and that the data of key$n is reliable 1: Means that programming key$n failed and the number of error bytes is over 6.*/
uint32_t key4_err_num: 3; /*The value of this signal means the number of error bytes.*/
uint32_t key4_fail: 1; /*0: Means no failure and that the data of key$n is reliable 1: Means that programming key$n failed and the number of error bytes is over 6.*/
};
uint32_t val;
} rd_rs_err0;
union {
struct {
uint32_t key5_err_num: 3; /*The value of this signal means the number of error bytes.*/
uint32_t key5_fail: 1; /*0: Means no failure and that the data of KEY5 is reliable 1: Means that programming user data failed and the number of error bytes is over 6.*/
uint32_t sys_part2_err_num: 3; /*The value of this signal means the number of error bytes.*/
uint32_t sys_part2_fail: 1; /*0: Means no failure and that the data of system part2 is reliable 1: Means that programming user data failed and the number of error bytes is over 6.*/
uint32_t reserved8: 24; /*Reserved.*/
};
uint32_t val;
} rd_rs_err1;
union {
struct {
uint32_t mem_force_pd: 1; /*Set this bit to force eFuse SRAM into power-saving mode.*/
uint32_t mem_clk_force_on: 1; /*Set this bit and force to activate clock signal of eFuse SRAM.*/
uint32_t mem_force_pu: 1; /*Set this bit to force eFuse SRAM into working mode.*/
uint32_t reserved3: 13; /*Reserved.*/
uint32_t clk_en: 1; /*Set this bit and force to enable clock signal of eFuse memory.*/
uint32_t reserved17: 15; /*Reserved.*/
};
uint32_t val;
} clk;
union {
struct {
uint32_t op_code: 16; /*0x5A5A: Operate programming command 0x5AA5: Operate read command.*/
uint32_t reserved16:16; /*Reserved.*/
};
uint32_t val;
} conf;
union {
struct {
uint32_t state: 4; /*Indicates the state of the eFuse state machine.*/
uint32_t otp_load_sw: 1; /*The value of OTP_LOAD_SW.*/
uint32_t otp_vddq_c_sync2: 1; /*The value of OTP_VDDQ_C_SYNC2.*/
uint32_t otp_strobe_sw: 1; /*The value of OTP_STROBE_SW.*/
uint32_t otp_csb_sw: 1; /*The value of OTP_CSB_SW.*/
uint32_t otp_pgenb_sw: 1; /*The value of OTP_PGENB_SW.*/
uint32_t otp_vddq_is_sw: 1; /*The value of OTP_VDDQ_IS_SW.*/
uint32_t repeat_err_cnt: 8; /*Indicates the number of error bits during programming BLOCK0.*/
uint32_t reserved18: 14; /*Reserved.*/
};
uint32_t val;
} status;
union {
struct {
uint32_t read_cmd: 1; /*Set this bit to send read command.*/
uint32_t pgm_cmd: 1; /*Set this bit to send programming command.*/
uint32_t blk_num: 4; /*The serial number of the block to be programmed. Value 0-10 corresponds to block number 0-10 respectively.*/
uint32_t reserved6: 26; /*Reserved.*/
};
uint32_t val;
} cmd;
union {
struct {
uint32_t read_done: 1; /*The raw bit signal for read_done interrupt.*/
uint32_t pgm_done: 1; /*The raw bit signal for pgm_done interrupt.*/
uint32_t reserved2: 30; /*Reserved.*/
};
uint32_t val;
} int_raw;
union {
struct {
uint32_t read_done: 1; /*The status signal for read_done interrupt.*/
uint32_t pgm_done: 1; /*The status signal for pgm_done interrupt.*/
uint32_t reserved2: 30; /*Reserved.*/
};
uint32_t val;
} int_st;
union {
struct {
uint32_t read_done: 1; /*The enable signal for read_done interrupt.*/
uint32_t pgm_done: 1; /*The enable signal for pgm_done interrupt.*/
uint32_t reserved2: 30; /*Reserved.*/
};
uint32_t val;
} int_ena;
union {
struct {
uint32_t read_done: 1; /*The clear signal for read_done interrupt.*/
uint32_t pgm_done: 1; /*The clear signal for pgm_done interrupt.*/
uint32_t reserved2: 30; /*Reserved.*/
};
uint32_t val;
} int_clr;
union {
struct {
uint32_t dac_clk_div: 8; /*Controls the division factor of the rising clock of the programming voltage.*/
uint32_t dac_clk_pad_sel: 1; /*Don't care.*/
uint32_t dac_num: 8; /*Controls the rising period of the programming voltage.*/
uint32_t oe_clr: 1; /*Reduces the power supply of the programming voltage.*/
uint32_t reserved18: 14; /*Reserved.*/
};
uint32_t val;
} dac_conf;
union {
struct {
uint32_t reserved0: 24; /*Configures the setup time of read operation.*/
uint32_t read_init_num: 8; /*Configures the initial read time of eFuse.*/
};
uint32_t val;
} rd_tim_conf;
union {
struct {
uint32_t reserved0: 8; /*Configures the setup time of programming operation.*/
uint32_t pwr_on_num:16; /*Configures the power up time for VDDQ.*/
uint32_t reserved24: 8; /*Reserved.*/
};
uint32_t val;
} wr_tim_conf1;
union {
struct {
uint32_t pwr_off_num:16; /*Configures the power outage time for VDDQ.*/
uint32_t reserved16: 16; /*Reserved.*/
};
uint32_t val;
} wr_tim_conf2;
uint32_t reserved_1f8;
union {
struct {
uint32_t date: 28; /*Stores eFuse version.*/
uint32_t reserved28: 4; /*Reserved.*/
};
uint32_t val;
} date;
} efuse_dev_t;
extern efuse_dev_t EFUSE;
#ifdef __cplusplus
}
#endif
#endif /* _SOC_EFUSE_STRUCT_H_ */

View File

@ -0,0 +1,992 @@
// 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.
#ifndef _SOC_EXTMEM_REG_H_
#define _SOC_EXTMEM_REG_H_
#ifdef __cplusplus
extern "C" {
#endif
#include "soc.h"
#define EXTMEM_ICACHE_CTRL_REG (DR_REG_EXTMEM_BASE + 0x000)
/* EXTMEM_ICACHE_ENABLE : R/W ;bitpos:[0] ;default: 1'b0 ; */
/*description: The bit is used to activate the data cache. 0: disable 1: enable*/
#define EXTMEM_ICACHE_ENABLE (BIT(0))
#define EXTMEM_ICACHE_ENABLE_M (BIT(0))
#define EXTMEM_ICACHE_ENABLE_V 0x1
#define EXTMEM_ICACHE_ENABLE_S 0
#define EXTMEM_ICACHE_CTRL1_REG (DR_REG_EXTMEM_BASE + 0x004)
/* EXTMEM_ICACHE_SHUT_DBUS : R/W ;bitpos:[1] ;default: 1'b1 ; */
/*description: The bit is used to disable core1 ibus 0: enable 1: disable*/
#define EXTMEM_ICACHE_SHUT_DBUS (BIT(1))
#define EXTMEM_ICACHE_SHUT_DBUS_M (BIT(1))
#define EXTMEM_ICACHE_SHUT_DBUS_V 0x1
#define EXTMEM_ICACHE_SHUT_DBUS_S 1
/* EXTMEM_ICACHE_SHUT_IBUS : R/W ;bitpos:[0] ;default: 1'b1 ; */
/*description: The bit is used to disable core0 ibus 0: enable 1: disable*/
#define EXTMEM_ICACHE_SHUT_IBUS (BIT(0))
#define EXTMEM_ICACHE_SHUT_IBUS_M (BIT(0))
#define EXTMEM_ICACHE_SHUT_IBUS_V 0x1
#define EXTMEM_ICACHE_SHUT_IBUS_S 0
#define EXTMEM_ICACHE_TAG_POWER_CTRL_REG (DR_REG_EXTMEM_BASE + 0x008)
/* EXTMEM_ICACHE_TAG_MEM_FORCE_PU : R/W ;bitpos:[2] ;default: 1'b1 ; */
/*description: The bit is used to power icache tag memory up 0: follow rtc_lslp 1: power up*/
#define EXTMEM_ICACHE_TAG_MEM_FORCE_PU (BIT(2))
#define EXTMEM_ICACHE_TAG_MEM_FORCE_PU_M (BIT(2))
#define EXTMEM_ICACHE_TAG_MEM_FORCE_PU_V 0x1
#define EXTMEM_ICACHE_TAG_MEM_FORCE_PU_S 2
/* EXTMEM_ICACHE_TAG_MEM_FORCE_PD : R/W ;bitpos:[1] ;default: 1'b0 ; */
/*description: The bit is used to power icache tag memory down 0: follow rtc_lslp
1: power down*/
#define EXTMEM_ICACHE_TAG_MEM_FORCE_PD (BIT(1))
#define EXTMEM_ICACHE_TAG_MEM_FORCE_PD_M (BIT(1))
#define EXTMEM_ICACHE_TAG_MEM_FORCE_PD_V 0x1
#define EXTMEM_ICACHE_TAG_MEM_FORCE_PD_S 1
/* EXTMEM_ICACHE_TAG_MEM_FORCE_ON : R/W ;bitpos:[0] ;default: 1'b1 ; */
/*description: The bit is used to close clock gating of icache tag memory.
1: close gating 0: open clock gating.*/
#define EXTMEM_ICACHE_TAG_MEM_FORCE_ON (BIT(0))
#define EXTMEM_ICACHE_TAG_MEM_FORCE_ON_M (BIT(0))
#define EXTMEM_ICACHE_TAG_MEM_FORCE_ON_V 0x1
#define EXTMEM_ICACHE_TAG_MEM_FORCE_ON_S 0
#define EXTMEM_ICACHE_PRELOCK_CTRL_REG (DR_REG_EXTMEM_BASE + 0x00C)
/* EXTMEM_ICACHE_PRELOCK_SCT1_EN : R/W ;bitpos:[1] ;default: 1'h0 ; */
/*description: The bit is used to enable the second section of prelock function.*/
#define EXTMEM_ICACHE_PRELOCK_SCT1_EN (BIT(1))
#define EXTMEM_ICACHE_PRELOCK_SCT1_EN_M (BIT(1))
#define EXTMEM_ICACHE_PRELOCK_SCT1_EN_V 0x1
#define EXTMEM_ICACHE_PRELOCK_SCT1_EN_S 1
/* EXTMEM_ICACHE_PRELOCK_SCT0_EN : R/W ;bitpos:[0] ;default: 1'h0 ; */
/*description: The bit is used to enable the first section of prelock function.*/
#define EXTMEM_ICACHE_PRELOCK_SCT0_EN (BIT(0))
#define EXTMEM_ICACHE_PRELOCK_SCT0_EN_M (BIT(0))
#define EXTMEM_ICACHE_PRELOCK_SCT0_EN_V 0x1
#define EXTMEM_ICACHE_PRELOCK_SCT0_EN_S 0
#define EXTMEM_ICACHE_PRELOCK_SCT0_ADDR_REG (DR_REG_EXTMEM_BASE + 0x010)
/* EXTMEM_ICACHE_PRELOCK_SCT0_ADDR : R/W ;bitpos:[31:0] ;default: 32'h0 ; */
/*description: The bits are used to configure the first start virtual address
of data prelock which is combined with ICACHE_PRELOCK_SCT0_SIZE_REG*/
#define EXTMEM_ICACHE_PRELOCK_SCT0_ADDR 0xFFFFFFFF
#define EXTMEM_ICACHE_PRELOCK_SCT0_ADDR_M ((EXTMEM_ICACHE_PRELOCK_SCT0_ADDR_V)<<(EXTMEM_ICACHE_PRELOCK_SCT0_ADDR_S))
#define EXTMEM_ICACHE_PRELOCK_SCT0_ADDR_V 0xFFFFFFFF
#define EXTMEM_ICACHE_PRELOCK_SCT0_ADDR_S 0
#define EXTMEM_ICACHE_PRELOCK_SCT1_ADDR_REG (DR_REG_EXTMEM_BASE + 0x014)
/* EXTMEM_ICACHE_PRELOCK_SCT1_ADDR : R/W ;bitpos:[31:0] ;default: 32'h0 ; */
/*description: The bits are used to configure the second start virtual address
of data prelock which is combined with ICACHE_PRELOCK_SCT1_SIZE_REG*/
#define EXTMEM_ICACHE_PRELOCK_SCT1_ADDR 0xFFFFFFFF
#define EXTMEM_ICACHE_PRELOCK_SCT1_ADDR_M ((EXTMEM_ICACHE_PRELOCK_SCT1_ADDR_V)<<(EXTMEM_ICACHE_PRELOCK_SCT1_ADDR_S))
#define EXTMEM_ICACHE_PRELOCK_SCT1_ADDR_V 0xFFFFFFFF
#define EXTMEM_ICACHE_PRELOCK_SCT1_ADDR_S 0
#define EXTMEM_ICACHE_PRELOCK_SCT_SIZE_REG (DR_REG_EXTMEM_BASE + 0x018)
/* EXTMEM_ICACHE_PRELOCK_SCT0_SIZE : R/W ;bitpos:[31:16] ;default: 16'h0 ; */
/*description: The bits are used to configure the first length of data locking
which is combined with ICACHE_PRELOCK_SCT0_ADDR_REG*/
#define EXTMEM_ICACHE_PRELOCK_SCT0_SIZE 0x0000FFFF
#define EXTMEM_ICACHE_PRELOCK_SCT0_SIZE_M ((EXTMEM_ICACHE_PRELOCK_SCT0_SIZE_V)<<(EXTMEM_ICACHE_PRELOCK_SCT0_SIZE_S))
#define EXTMEM_ICACHE_PRELOCK_SCT0_SIZE_V 0xFFFF
#define EXTMEM_ICACHE_PRELOCK_SCT0_SIZE_S 16
/* EXTMEM_ICACHE_PRELOCK_SCT1_SIZE : R/W ;bitpos:[15:0] ;default: 16'h0 ; */
/*description: The bits are used to configure the second length of data locking
which is combined with ICACHE_PRELOCK_SCT1_ADDR_REG*/
#define EXTMEM_ICACHE_PRELOCK_SCT1_SIZE 0x0000FFFF
#define EXTMEM_ICACHE_PRELOCK_SCT1_SIZE_M ((EXTMEM_ICACHE_PRELOCK_SCT1_SIZE_V)<<(EXTMEM_ICACHE_PRELOCK_SCT1_SIZE_S))
#define EXTMEM_ICACHE_PRELOCK_SCT1_SIZE_V 0xFFFF
#define EXTMEM_ICACHE_PRELOCK_SCT1_SIZE_S 0
#define EXTMEM_ICACHE_LOCK_CTRL_REG (DR_REG_EXTMEM_BASE + 0x01C)
/* EXTMEM_ICACHE_LOCK_DONE : RO ;bitpos:[2] ;default: 1'b1 ; */
/*description: The bit is used to indicate unlock/lock operation is finished.*/
#define EXTMEM_ICACHE_LOCK_DONE (BIT(2))
#define EXTMEM_ICACHE_LOCK_DONE_M (BIT(2))
#define EXTMEM_ICACHE_LOCK_DONE_V 0x1
#define EXTMEM_ICACHE_LOCK_DONE_S 2
/* EXTMEM_ICACHE_UNLOCK_ENA : R/W ;bitpos:[1] ;default: 1'b0 ; */
/*description: The bit is used to enable unlock operation. It will be cleared
by hardware after unlock operation done.*/
#define EXTMEM_ICACHE_UNLOCK_ENA (BIT(1))
#define EXTMEM_ICACHE_UNLOCK_ENA_M (BIT(1))
#define EXTMEM_ICACHE_UNLOCK_ENA_V 0x1
#define EXTMEM_ICACHE_UNLOCK_ENA_S 1
/* EXTMEM_ICACHE_LOCK_ENA : R/W ;bitpos:[0] ;default: 1'b0 ; */
/*description: The bit is used to enable lock operation. It will be cleared
by hardware after lock operation done.*/
#define EXTMEM_ICACHE_LOCK_ENA (BIT(0))
#define EXTMEM_ICACHE_LOCK_ENA_M (BIT(0))
#define EXTMEM_ICACHE_LOCK_ENA_V 0x1
#define EXTMEM_ICACHE_LOCK_ENA_S 0
#define EXTMEM_ICACHE_LOCK_ADDR_REG (DR_REG_EXTMEM_BASE + 0x020)
/* EXTMEM_ICACHE_LOCK_ADDR : R/W ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: The bits are used to configure the start virtual address for
lock operations. It should be combined with ICACHE_LOCK_SIZE_REG.*/
#define EXTMEM_ICACHE_LOCK_ADDR 0xFFFFFFFF
#define EXTMEM_ICACHE_LOCK_ADDR_M ((EXTMEM_ICACHE_LOCK_ADDR_V)<<(EXTMEM_ICACHE_LOCK_ADDR_S))
#define EXTMEM_ICACHE_LOCK_ADDR_V 0xFFFFFFFF
#define EXTMEM_ICACHE_LOCK_ADDR_S 0
#define EXTMEM_ICACHE_LOCK_SIZE_REG (DR_REG_EXTMEM_BASE + 0x024)
/* EXTMEM_ICACHE_LOCK_SIZE : R/W ;bitpos:[15:0] ;default: 16'h0 ; */
/*description: The bits are used to configure the length for lock operations.
The bits are the counts of cache block. It should be combined with ICACHE_LOCK_ADDR_REG.*/
#define EXTMEM_ICACHE_LOCK_SIZE 0x0000FFFF
#define EXTMEM_ICACHE_LOCK_SIZE_M ((EXTMEM_ICACHE_LOCK_SIZE_V)<<(EXTMEM_ICACHE_LOCK_SIZE_S))
#define EXTMEM_ICACHE_LOCK_SIZE_V 0xFFFF
#define EXTMEM_ICACHE_LOCK_SIZE_S 0
#define EXTMEM_ICACHE_SYNC_CTRL_REG (DR_REG_EXTMEM_BASE + 0x028)
/* EXTMEM_ICACHE_SYNC_DONE : RO ;bitpos:[1] ;default: 1'b0 ; */
/*description: The bit is used to indicate invalidate operation is finished.*/
#define EXTMEM_ICACHE_SYNC_DONE (BIT(1))
#define EXTMEM_ICACHE_SYNC_DONE_M (BIT(1))
#define EXTMEM_ICACHE_SYNC_DONE_V 0x1
#define EXTMEM_ICACHE_SYNC_DONE_S 1
/* EXTMEM_ICACHE_INVALIDATE_ENA : R/W ;bitpos:[0] ;default: 1'b1 ; */
/*description: The bit is used to enable invalidate operation. It will be cleared
by hardware after invalidate operation done.*/
#define EXTMEM_ICACHE_INVALIDATE_ENA (BIT(0))
#define EXTMEM_ICACHE_INVALIDATE_ENA_M (BIT(0))
#define EXTMEM_ICACHE_INVALIDATE_ENA_V 0x1
#define EXTMEM_ICACHE_INVALIDATE_ENA_S 0
#define EXTMEM_ICACHE_SYNC_ADDR_REG (DR_REG_EXTMEM_BASE + 0x02C)
/* EXTMEM_ICACHE_SYNC_ADDR : R/W ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: The bits are used to configure the start virtual address for
clean operations. It should be combined with ICACHE_SYNC_SIZE_REG.*/
#define EXTMEM_ICACHE_SYNC_ADDR 0xFFFFFFFF
#define EXTMEM_ICACHE_SYNC_ADDR_M ((EXTMEM_ICACHE_SYNC_ADDR_V)<<(EXTMEM_ICACHE_SYNC_ADDR_S))
#define EXTMEM_ICACHE_SYNC_ADDR_V 0xFFFFFFFF
#define EXTMEM_ICACHE_SYNC_ADDR_S 0
#define EXTMEM_ICACHE_SYNC_SIZE_REG (DR_REG_EXTMEM_BASE + 0x030)
/* EXTMEM_ICACHE_SYNC_SIZE : R/W ;bitpos:[22:0] ;default: 23'h0 ; */
/*description: The bits are used to configure the length for sync operations.
The bits are the counts of cache block. It should be combined with ICACHE_SYNC_ADDR_REG.*/
#define EXTMEM_ICACHE_SYNC_SIZE 0x007FFFFF
#define EXTMEM_ICACHE_SYNC_SIZE_M ((EXTMEM_ICACHE_SYNC_SIZE_V)<<(EXTMEM_ICACHE_SYNC_SIZE_S))
#define EXTMEM_ICACHE_SYNC_SIZE_V 0x7FFFFF
#define EXTMEM_ICACHE_SYNC_SIZE_S 0
#define EXTMEM_ICACHE_PRELOAD_CTRL_REG (DR_REG_EXTMEM_BASE + 0x034)
/* EXTMEM_ICACHE_PRELOAD_ORDER : R/W ;bitpos:[2] ;default: 1'b0 ; */
/*description: The bit is used to configure the direction of preload operation.
1: descending 0: ascending.*/
#define EXTMEM_ICACHE_PRELOAD_ORDER (BIT(2))
#define EXTMEM_ICACHE_PRELOAD_ORDER_M (BIT(2))
#define EXTMEM_ICACHE_PRELOAD_ORDER_V 0x1
#define EXTMEM_ICACHE_PRELOAD_ORDER_S 2
/* EXTMEM_ICACHE_PRELOAD_DONE : RO ;bitpos:[1] ;default: 1'b1 ; */
/*description: The bit is used to indicate preload operation is finished.*/
#define EXTMEM_ICACHE_PRELOAD_DONE (BIT(1))
#define EXTMEM_ICACHE_PRELOAD_DONE_M (BIT(1))
#define EXTMEM_ICACHE_PRELOAD_DONE_V 0x1
#define EXTMEM_ICACHE_PRELOAD_DONE_S 1
/* EXTMEM_ICACHE_PRELOAD_ENA : R/W ;bitpos:[0] ;default: 1'b0 ; */
/*description: The bit is used to enable preload operation. It will be cleared
by hardware after preload operation done.*/
#define EXTMEM_ICACHE_PRELOAD_ENA (BIT(0))
#define EXTMEM_ICACHE_PRELOAD_ENA_M (BIT(0))
#define EXTMEM_ICACHE_PRELOAD_ENA_V 0x1
#define EXTMEM_ICACHE_PRELOAD_ENA_S 0
#define EXTMEM_ICACHE_PRELOAD_ADDR_REG (DR_REG_EXTMEM_BASE + 0x038)
/* EXTMEM_ICACHE_PRELOAD_ADDR : R/W ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: The bits are used to configure the start virtual address for
preload operation. It should be combined with ICACHE_PRELOAD_SIZE_REG.*/
#define EXTMEM_ICACHE_PRELOAD_ADDR 0xFFFFFFFF
#define EXTMEM_ICACHE_PRELOAD_ADDR_M ((EXTMEM_ICACHE_PRELOAD_ADDR_V)<<(EXTMEM_ICACHE_PRELOAD_ADDR_S))
#define EXTMEM_ICACHE_PRELOAD_ADDR_V 0xFFFFFFFF
#define EXTMEM_ICACHE_PRELOAD_ADDR_S 0
#define EXTMEM_ICACHE_PRELOAD_SIZE_REG (DR_REG_EXTMEM_BASE + 0x03C)
/* EXTMEM_ICACHE_PRELOAD_SIZE : R/W ;bitpos:[15:0] ;default: 16'h0 ; */
/*description: The bits are used to configure the length for preload operation.
The bits are the counts of cache block. It should be combined with ICACHE_PRELOAD_ADDR_REG..*/
#define EXTMEM_ICACHE_PRELOAD_SIZE 0x0000FFFF
#define EXTMEM_ICACHE_PRELOAD_SIZE_M ((EXTMEM_ICACHE_PRELOAD_SIZE_V)<<(EXTMEM_ICACHE_PRELOAD_SIZE_S))
#define EXTMEM_ICACHE_PRELOAD_SIZE_V 0xFFFF
#define EXTMEM_ICACHE_PRELOAD_SIZE_S 0
#define EXTMEM_ICACHE_AUTOLOAD_CTRL_REG (DR_REG_EXTMEM_BASE + 0x040)
/* EXTMEM_ICACHE_AUTOLOAD_RQST : R/W ;bitpos:[6:5] ;default: 2'b0 ; */
/*description: The bits are used to configure trigger conditions for autoload.
0/3: cache miss 1: cache hit 2: both cache miss and hit.*/
#define EXTMEM_ICACHE_AUTOLOAD_RQST 0x00000003
#define EXTMEM_ICACHE_AUTOLOAD_RQST_M ((EXTMEM_ICACHE_AUTOLOAD_RQST_V)<<(EXTMEM_ICACHE_AUTOLOAD_RQST_S))
#define EXTMEM_ICACHE_AUTOLOAD_RQST_V 0x3
#define EXTMEM_ICACHE_AUTOLOAD_RQST_S 5
/* EXTMEM_ICACHE_AUTOLOAD_ORDER : R/W ;bitpos:[4] ;default: 1'b0 ; */
/*description: The bits are used to configure the direction of autoload. 1:
descending 0: ascending.*/
#define EXTMEM_ICACHE_AUTOLOAD_ORDER (BIT(4))
#define EXTMEM_ICACHE_AUTOLOAD_ORDER_M (BIT(4))
#define EXTMEM_ICACHE_AUTOLOAD_ORDER_V 0x1
#define EXTMEM_ICACHE_AUTOLOAD_ORDER_S 4
/* EXTMEM_ICACHE_AUTOLOAD_DONE : RO ;bitpos:[3] ;default: 1'b1 ; */
/*description: The bit is used to indicate autoload operation is finished.*/
#define EXTMEM_ICACHE_AUTOLOAD_DONE (BIT(3))
#define EXTMEM_ICACHE_AUTOLOAD_DONE_M (BIT(3))
#define EXTMEM_ICACHE_AUTOLOAD_DONE_V 0x1
#define EXTMEM_ICACHE_AUTOLOAD_DONE_S 3
/* EXTMEM_ICACHE_AUTOLOAD_ENA : R/W ;bitpos:[2] ;default: 1'b0 ; */
/*description: The bit is used to enable and disable autoload operation. It
is combined with icache_autoload_done. 1: enable 0: disable.*/
#define EXTMEM_ICACHE_AUTOLOAD_ENA (BIT(2))
#define EXTMEM_ICACHE_AUTOLOAD_ENA_M (BIT(2))
#define EXTMEM_ICACHE_AUTOLOAD_ENA_V 0x1
#define EXTMEM_ICACHE_AUTOLOAD_ENA_S 2
/* EXTMEM_ICACHE_AUTOLOAD_SCT1_ENA : R/W ;bitpos:[1] ;default: 1'b0 ; */
/*description: The bits are used to enable the second section for autoload operation.*/
#define EXTMEM_ICACHE_AUTOLOAD_SCT1_ENA (BIT(1))
#define EXTMEM_ICACHE_AUTOLOAD_SCT1_ENA_M (BIT(1))
#define EXTMEM_ICACHE_AUTOLOAD_SCT1_ENA_V 0x1
#define EXTMEM_ICACHE_AUTOLOAD_SCT1_ENA_S 1
/* EXTMEM_ICACHE_AUTOLOAD_SCT0_ENA : R/W ;bitpos:[0] ;default: 1'b0 ; */
/*description: The bits are used to enable the first section for autoload operation.*/
#define EXTMEM_ICACHE_AUTOLOAD_SCT0_ENA (BIT(0))
#define EXTMEM_ICACHE_AUTOLOAD_SCT0_ENA_M (BIT(0))
#define EXTMEM_ICACHE_AUTOLOAD_SCT0_ENA_V 0x1
#define EXTMEM_ICACHE_AUTOLOAD_SCT0_ENA_S 0
#define EXTMEM_ICACHE_AUTOLOAD_SCT0_ADDR_REG (DR_REG_EXTMEM_BASE + 0x044)
/* EXTMEM_ICACHE_AUTOLOAD_SCT0_ADDR : R/W ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: The bits are used to configure the start virtual address of the
first section for autoload operation. It should be combined with icache_autoload_sct0_ena.*/
#define EXTMEM_ICACHE_AUTOLOAD_SCT0_ADDR 0xFFFFFFFF
#define EXTMEM_ICACHE_AUTOLOAD_SCT0_ADDR_M ((EXTMEM_ICACHE_AUTOLOAD_SCT0_ADDR_V)<<(EXTMEM_ICACHE_AUTOLOAD_SCT0_ADDR_S))
#define EXTMEM_ICACHE_AUTOLOAD_SCT0_ADDR_V 0xFFFFFFFF
#define EXTMEM_ICACHE_AUTOLOAD_SCT0_ADDR_S 0
#define EXTMEM_ICACHE_AUTOLOAD_SCT0_SIZE_REG (DR_REG_EXTMEM_BASE + 0x048)
/* EXTMEM_ICACHE_AUTOLOAD_SCT0_SIZE : R/W ;bitpos:[26:0] ;default: 27'h0 ; */
/*description: The bits are used to configure the length of the first section
for autoload operation. It should be combined with icache_autoload_sct0_ena.*/
#define EXTMEM_ICACHE_AUTOLOAD_SCT0_SIZE 0x07FFFFFF
#define EXTMEM_ICACHE_AUTOLOAD_SCT0_SIZE_M ((EXTMEM_ICACHE_AUTOLOAD_SCT0_SIZE_V)<<(EXTMEM_ICACHE_AUTOLOAD_SCT0_SIZE_S))
#define EXTMEM_ICACHE_AUTOLOAD_SCT0_SIZE_V 0x7FFFFFF
#define EXTMEM_ICACHE_AUTOLOAD_SCT0_SIZE_S 0
#define EXTMEM_ICACHE_AUTOLOAD_SCT1_ADDR_REG (DR_REG_EXTMEM_BASE + 0x04C)
/* EXTMEM_ICACHE_AUTOLOAD_SCT1_ADDR : R/W ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: The bits are used to configure the start virtual address of the
second section for autoload operation. It should be combined with icache_autoload_sct1_ena.*/
#define EXTMEM_ICACHE_AUTOLOAD_SCT1_ADDR 0xFFFFFFFF
#define EXTMEM_ICACHE_AUTOLOAD_SCT1_ADDR_M ((EXTMEM_ICACHE_AUTOLOAD_SCT1_ADDR_V)<<(EXTMEM_ICACHE_AUTOLOAD_SCT1_ADDR_S))
#define EXTMEM_ICACHE_AUTOLOAD_SCT1_ADDR_V 0xFFFFFFFF
#define EXTMEM_ICACHE_AUTOLOAD_SCT1_ADDR_S 0
#define EXTMEM_ICACHE_AUTOLOAD_SCT1_SIZE_REG (DR_REG_EXTMEM_BASE + 0x050)
/* EXTMEM_ICACHE_AUTOLOAD_SCT1_SIZE : R/W ;bitpos:[26:0] ;default: 27'h0 ; */
/*description: The bits are used to configure the length of the second section
for autoload operation. It should be combined with icache_autoload_sct1_ena.*/
#define EXTMEM_ICACHE_AUTOLOAD_SCT1_SIZE 0x07FFFFFF
#define EXTMEM_ICACHE_AUTOLOAD_SCT1_SIZE_M ((EXTMEM_ICACHE_AUTOLOAD_SCT1_SIZE_V)<<(EXTMEM_ICACHE_AUTOLOAD_SCT1_SIZE_S))
#define EXTMEM_ICACHE_AUTOLOAD_SCT1_SIZE_V 0x7FFFFFF
#define EXTMEM_ICACHE_AUTOLOAD_SCT1_SIZE_S 0
#define EXTMEM_IBUS_TO_FLASH_START_VADDR_REG (DR_REG_EXTMEM_BASE + 0x054)
/* EXTMEM_IBUS_TO_FLASH_START_VADDR : R/W ;bitpos:[31:0] ;default: 32'h42000000 ; */
/*description: The bits are used to configure the start virtual address of ibus
to access flash. The register is used to give constraints to ibus access counter.*/
#define EXTMEM_IBUS_TO_FLASH_START_VADDR 0xFFFFFFFF
#define EXTMEM_IBUS_TO_FLASH_START_VADDR_M ((EXTMEM_IBUS_TO_FLASH_START_VADDR_V)<<(EXTMEM_IBUS_TO_FLASH_START_VADDR_S))
#define EXTMEM_IBUS_TO_FLASH_START_VADDR_V 0xFFFFFFFF
#define EXTMEM_IBUS_TO_FLASH_START_VADDR_S 0
#define EXTMEM_IBUS_TO_FLASH_END_VADDR_REG (DR_REG_EXTMEM_BASE + 0x058)
/* EXTMEM_IBUS_TO_FLASH_END_VADDR : R/W ;bitpos:[31:0] ;default: 32'h427FFFFF ; */
/*description: The bits are used to configure the end virtual address of ibus
to access flash. The register is used to give constraints to ibus access counter.*/
#define EXTMEM_IBUS_TO_FLASH_END_VADDR 0xFFFFFFFF
#define EXTMEM_IBUS_TO_FLASH_END_VADDR_M ((EXTMEM_IBUS_TO_FLASH_END_VADDR_V)<<(EXTMEM_IBUS_TO_FLASH_END_VADDR_S))
#define EXTMEM_IBUS_TO_FLASH_END_VADDR_V 0xFFFFFFFF
#define EXTMEM_IBUS_TO_FLASH_END_VADDR_S 0
#define EXTMEM_DBUS_TO_FLASH_START_VADDR_REG (DR_REG_EXTMEM_BASE + 0x05C)
/* EXTMEM_DBUS_TO_FLASH_START_VADDR : R/W ;bitpos:[31:0] ;default: 32'h3C000000 ; */
/*description: The bits are used to configure the start virtual address of dbus
to access flash. The register is used to give constraints to dbus access counter.*/
#define EXTMEM_DBUS_TO_FLASH_START_VADDR 0xFFFFFFFF
#define EXTMEM_DBUS_TO_FLASH_START_VADDR_M ((EXTMEM_DBUS_TO_FLASH_START_VADDR_V)<<(EXTMEM_DBUS_TO_FLASH_START_VADDR_S))
#define EXTMEM_DBUS_TO_FLASH_START_VADDR_V 0xFFFFFFFF
#define EXTMEM_DBUS_TO_FLASH_START_VADDR_S 0
#define EXTMEM_DBUS_TO_FLASH_END_VADDR_REG (DR_REG_EXTMEM_BASE + 0x060)
/* EXTMEM_DBUS_TO_FLASH_END_VADDR : R/W ;bitpos:[31:0] ;default: 32'h3C7FFFFF ; */
/*description: The bits are used to configure the end virtual address of dbus
to access flash. The register is used to give constraints to dbus access counter.*/
#define EXTMEM_DBUS_TO_FLASH_END_VADDR 0xFFFFFFFF
#define EXTMEM_DBUS_TO_FLASH_END_VADDR_M ((EXTMEM_DBUS_TO_FLASH_END_VADDR_V)<<(EXTMEM_DBUS_TO_FLASH_END_VADDR_S))
#define EXTMEM_DBUS_TO_FLASH_END_VADDR_V 0xFFFFFFFF
#define EXTMEM_DBUS_TO_FLASH_END_VADDR_S 0
#define EXTMEM_CACHE_ACS_CNT_CLR_REG (DR_REG_EXTMEM_BASE + 0x064)
/* EXTMEM_DBUS_ACS_CNT_CLR : WOD ;bitpos:[1] ;default: 1'b0 ; */
/*description: The bit is used to clear dbus counter.*/
#define EXTMEM_DBUS_ACS_CNT_CLR (BIT(1))
#define EXTMEM_DBUS_ACS_CNT_CLR_M (BIT(1))
#define EXTMEM_DBUS_ACS_CNT_CLR_V 0x1
#define EXTMEM_DBUS_ACS_CNT_CLR_S 1
/* EXTMEM_IBUS_ACS_CNT_CLR : WOD ;bitpos:[0] ;default: 1'b0 ; */
/*description: The bit is used to clear ibus counter.*/
#define EXTMEM_IBUS_ACS_CNT_CLR (BIT(0))
#define EXTMEM_IBUS_ACS_CNT_CLR_M (BIT(0))
#define EXTMEM_IBUS_ACS_CNT_CLR_V 0x1
#define EXTMEM_IBUS_ACS_CNT_CLR_S 0
#define EXTMEM_IBUS_ACS_MISS_CNT_REG (DR_REG_EXTMEM_BASE + 0x068)
/* EXTMEM_IBUS_ACS_MISS_CNT : RO ;bitpos:[31:0] ;default: 32'h0 ; */
/*description: The bits are used to count the number of the cache miss caused
by ibus access flash.*/
#define EXTMEM_IBUS_ACS_MISS_CNT 0xFFFFFFFF
#define EXTMEM_IBUS_ACS_MISS_CNT_M ((EXTMEM_IBUS_ACS_MISS_CNT_V)<<(EXTMEM_IBUS_ACS_MISS_CNT_S))
#define EXTMEM_IBUS_ACS_MISS_CNT_V 0xFFFFFFFF
#define EXTMEM_IBUS_ACS_MISS_CNT_S 0
#define EXTMEM_IBUS_ACS_CNT_REG (DR_REG_EXTMEM_BASE + 0x06C)
/* EXTMEM_IBUS_ACS_CNT : RO ;bitpos:[31:0] ;default: 32'h0 ; */
/*description: The bits are used to count the number of ibus access flash through icache.*/
#define EXTMEM_IBUS_ACS_CNT 0xFFFFFFFF
#define EXTMEM_IBUS_ACS_CNT_M ((EXTMEM_IBUS_ACS_CNT_V)<<(EXTMEM_IBUS_ACS_CNT_S))
#define EXTMEM_IBUS_ACS_CNT_V 0xFFFFFFFF
#define EXTMEM_IBUS_ACS_CNT_S 0
#define EXTMEM_DBUS_ACS_FLASH_MISS_CNT_REG (DR_REG_EXTMEM_BASE + 0x070)
/* EXTMEM_DBUS_ACS_FLASH_MISS_CNT : RO ;bitpos:[31:0] ;default: 32'h0 ; */
/*description: The bits are used to count the number of the cache miss caused
by dbus access flash.*/
#define EXTMEM_DBUS_ACS_FLASH_MISS_CNT 0xFFFFFFFF
#define EXTMEM_DBUS_ACS_FLASH_MISS_CNT_M ((EXTMEM_DBUS_ACS_FLASH_MISS_CNT_V)<<(EXTMEM_DBUS_ACS_FLASH_MISS_CNT_S))
#define EXTMEM_DBUS_ACS_FLASH_MISS_CNT_V 0xFFFFFFFF
#define EXTMEM_DBUS_ACS_FLASH_MISS_CNT_S 0
#define EXTMEM_DBUS_ACS_CNT_REG (DR_REG_EXTMEM_BASE + 0x074)
/* EXTMEM_DBUS_ACS_CNT : RO ;bitpos:[31:0] ;default: 32'h0 ; */
/*description: The bits are used to count the number of dbus access flash through icache.*/
#define EXTMEM_DBUS_ACS_CNT 0xFFFFFFFF
#define EXTMEM_DBUS_ACS_CNT_M ((EXTMEM_DBUS_ACS_CNT_V)<<(EXTMEM_DBUS_ACS_CNT_S))
#define EXTMEM_DBUS_ACS_CNT_V 0xFFFFFFFF
#define EXTMEM_DBUS_ACS_CNT_S 0
#define EXTMEM_CACHE_ILG_INT_ENA_REG (DR_REG_EXTMEM_BASE + 0x078)
/* EXTMEM_DBUS_CNT_OVF_INT_ENA : R/W ;bitpos:[8] ;default: 1'b0 ; */
/*description: The bit is used to enable interrupt by dbus counter overflow.*/
#define EXTMEM_DBUS_CNT_OVF_INT_ENA (BIT(8))
#define EXTMEM_DBUS_CNT_OVF_INT_ENA_M (BIT(8))
#define EXTMEM_DBUS_CNT_OVF_INT_ENA_V 0x1
#define EXTMEM_DBUS_CNT_OVF_INT_ENA_S 8
/* EXTMEM_IBUS_CNT_OVF_INT_ENA : R/W ;bitpos:[7] ;default: 1'b0 ; */
/*description: The bit is used to enable interrupt by ibus counter overflow.*/
#define EXTMEM_IBUS_CNT_OVF_INT_ENA (BIT(7))
#define EXTMEM_IBUS_CNT_OVF_INT_ENA_M (BIT(7))
#define EXTMEM_IBUS_CNT_OVF_INT_ENA_V 0x1
#define EXTMEM_IBUS_CNT_OVF_INT_ENA_S 7
/* EXTMEM_MMU_ENTRY_FAULT_INT_ENA : R/W ;bitpos:[5] ;default: 1'b0 ; */
/*description: The bit is used to enable interrupt by mmu entry fault.*/
#define EXTMEM_MMU_ENTRY_FAULT_INT_ENA (BIT(5))
#define EXTMEM_MMU_ENTRY_FAULT_INT_ENA_M (BIT(5))
#define EXTMEM_MMU_ENTRY_FAULT_INT_ENA_V 0x1
#define EXTMEM_MMU_ENTRY_FAULT_INT_ENA_S 5
/* EXTMEM_ICACHE_PRELOAD_OP_FAULT_INT_ENA : R/W ;bitpos:[1] ;default: 1'b0 ; */
/*description: The bit is used to enable interrupt by preload configurations fault.*/
#define EXTMEM_ICACHE_PRELOAD_OP_FAULT_INT_ENA (BIT(1))
#define EXTMEM_ICACHE_PRELOAD_OP_FAULT_INT_ENA_M (BIT(1))
#define EXTMEM_ICACHE_PRELOAD_OP_FAULT_INT_ENA_V 0x1
#define EXTMEM_ICACHE_PRELOAD_OP_FAULT_INT_ENA_S 1
/* EXTMEM_ICACHE_SYNC_OP_FAULT_INT_ENA : R/W ;bitpos:[0] ;default: 1'b0 ; */
/*description: The bit is used to enable interrupt by sync configurations fault.*/
#define EXTMEM_ICACHE_SYNC_OP_FAULT_INT_ENA (BIT(0))
#define EXTMEM_ICACHE_SYNC_OP_FAULT_INT_ENA_M (BIT(0))
#define EXTMEM_ICACHE_SYNC_OP_FAULT_INT_ENA_V 0x1
#define EXTMEM_ICACHE_SYNC_OP_FAULT_INT_ENA_S 0
#define EXTMEM_CACHE_ILG_INT_CLR_REG (DR_REG_EXTMEM_BASE + 0x07C)
/* EXTMEM_DBUS_CNT_OVF_INT_CLR : WOD ;bitpos:[8] ;default: 1'b0 ; */
/*description: The bit is used to clear interrupt by dbus counter overflow.*/
#define EXTMEM_DBUS_CNT_OVF_INT_CLR (BIT(8))
#define EXTMEM_DBUS_CNT_OVF_INT_CLR_M (BIT(8))
#define EXTMEM_DBUS_CNT_OVF_INT_CLR_V 0x1
#define EXTMEM_DBUS_CNT_OVF_INT_CLR_S 8
/* EXTMEM_IBUS_CNT_OVF_INT_CLR : WOD ;bitpos:[7] ;default: 1'b0 ; */
/*description: The bit is used to clear interrupt by ibus counter overflow.*/
#define EXTMEM_IBUS_CNT_OVF_INT_CLR (BIT(7))
#define EXTMEM_IBUS_CNT_OVF_INT_CLR_M (BIT(7))
#define EXTMEM_IBUS_CNT_OVF_INT_CLR_V 0x1
#define EXTMEM_IBUS_CNT_OVF_INT_CLR_S 7
/* EXTMEM_MMU_ENTRY_FAULT_INT_CLR : WOD ;bitpos:[5] ;default: 1'b0 ; */
/*description: The bit is used to clear interrupt by mmu entry fault.*/
#define EXTMEM_MMU_ENTRY_FAULT_INT_CLR (BIT(5))
#define EXTMEM_MMU_ENTRY_FAULT_INT_CLR_M (BIT(5))
#define EXTMEM_MMU_ENTRY_FAULT_INT_CLR_V 0x1
#define EXTMEM_MMU_ENTRY_FAULT_INT_CLR_S 5
/* EXTMEM_ICACHE_PRELOAD_OP_FAULT_INT_CLR : WOD ;bitpos:[1] ;default: 1'b0 ; */
/*description: The bit is used to clear interrupt by preload configurations fault.*/
#define EXTMEM_ICACHE_PRELOAD_OP_FAULT_INT_CLR (BIT(1))
#define EXTMEM_ICACHE_PRELOAD_OP_FAULT_INT_CLR_M (BIT(1))
#define EXTMEM_ICACHE_PRELOAD_OP_FAULT_INT_CLR_V 0x1
#define EXTMEM_ICACHE_PRELOAD_OP_FAULT_INT_CLR_S 1
/* EXTMEM_ICACHE_SYNC_OP_FAULT_INT_CLR : WOD ;bitpos:[0] ;default: 1'b0 ; */
/*description: The bit is used to clear interrupt by sync configurations fault.*/
#define EXTMEM_ICACHE_SYNC_OP_FAULT_INT_CLR (BIT(0))
#define EXTMEM_ICACHE_SYNC_OP_FAULT_INT_CLR_M (BIT(0))
#define EXTMEM_ICACHE_SYNC_OP_FAULT_INT_CLR_V 0x1
#define EXTMEM_ICACHE_SYNC_OP_FAULT_INT_CLR_S 0
#define EXTMEM_CACHE_ILG_INT_ST_REG (DR_REG_EXTMEM_BASE + 0x080)
/* EXTMEM_DBUS_ACS_FLASH_MISS_CNT_OVF_ST : RO ;bitpos:[10] ;default: 1'b0 ; */
/*description: The bit is used to indicate interrupt by dbus access flash miss
counter overflow.*/
#define EXTMEM_DBUS_ACS_FLASH_MISS_CNT_OVF_ST (BIT(10))
#define EXTMEM_DBUS_ACS_FLASH_MISS_CNT_OVF_ST_M (BIT(10))
#define EXTMEM_DBUS_ACS_FLASH_MISS_CNT_OVF_ST_V 0x1
#define EXTMEM_DBUS_ACS_FLASH_MISS_CNT_OVF_ST_S 10
/* EXTMEM_DBUS_ACS_CNT_OVF_ST : RO ;bitpos:[9] ;default: 1'b0 ; */
/*description: The bit is used to indicate interrupt by dbus access flash/spiram
counter overflow.*/
#define EXTMEM_DBUS_ACS_CNT_OVF_ST (BIT(9))
#define EXTMEM_DBUS_ACS_CNT_OVF_ST_M (BIT(9))
#define EXTMEM_DBUS_ACS_CNT_OVF_ST_V 0x1
#define EXTMEM_DBUS_ACS_CNT_OVF_ST_S 9
/* EXTMEM_IBUS_ACS_MISS_CNT_OVF_ST : RO ;bitpos:[8] ;default: 1'b0 ; */
/*description: The bit is used to indicate interrupt by ibus access flash/spiram
miss counter overflow.*/
#define EXTMEM_IBUS_ACS_MISS_CNT_OVF_ST (BIT(8))
#define EXTMEM_IBUS_ACS_MISS_CNT_OVF_ST_M (BIT(8))
#define EXTMEM_IBUS_ACS_MISS_CNT_OVF_ST_V 0x1
#define EXTMEM_IBUS_ACS_MISS_CNT_OVF_ST_S 8
/* EXTMEM_IBUS_ACS_CNT_OVF_ST : RO ;bitpos:[7] ;default: 1'b0 ; */
/*description: The bit is used to indicate interrupt by ibus access flash/spiram
counter overflow.*/
#define EXTMEM_IBUS_ACS_CNT_OVF_ST (BIT(7))
#define EXTMEM_IBUS_ACS_CNT_OVF_ST_M (BIT(7))
#define EXTMEM_IBUS_ACS_CNT_OVF_ST_V 0x1
#define EXTMEM_IBUS_ACS_CNT_OVF_ST_S 7
/* EXTMEM_MMU_ENTRY_FAULT_ST : RO ;bitpos:[5] ;default: 1'b0 ; */
/*description: The bit is used to indicate interrupt by mmu entry fault.*/
#define EXTMEM_MMU_ENTRY_FAULT_ST (BIT(5))
#define EXTMEM_MMU_ENTRY_FAULT_ST_M (BIT(5))
#define EXTMEM_MMU_ENTRY_FAULT_ST_V 0x1
#define EXTMEM_MMU_ENTRY_FAULT_ST_S 5
/* EXTMEM_ICACHE_PRELOAD_OP_FAULT_ST : RO ;bitpos:[1] ;default: 1'b0 ; */
/*description: The bit is used to indicate interrupt by preload configurations fault.*/
#define EXTMEM_ICACHE_PRELOAD_OP_FAULT_ST (BIT(1))
#define EXTMEM_ICACHE_PRELOAD_OP_FAULT_ST_M (BIT(1))
#define EXTMEM_ICACHE_PRELOAD_OP_FAULT_ST_V 0x1
#define EXTMEM_ICACHE_PRELOAD_OP_FAULT_ST_S 1
/* EXTMEM_ICACHE_SYNC_OP_FAULT_ST : RO ;bitpos:[0] ;default: 1'b0 ; */
/*description: The bit is used to indicate interrupt by sync configurations fault.*/
#define EXTMEM_ICACHE_SYNC_OP_FAULT_ST (BIT(0))
#define EXTMEM_ICACHE_SYNC_OP_FAULT_ST_M (BIT(0))
#define EXTMEM_ICACHE_SYNC_OP_FAULT_ST_V 0x1
#define EXTMEM_ICACHE_SYNC_OP_FAULT_ST_S 0
#define EXTMEM_CORE0_ACS_CACHE_INT_ENA_REG (DR_REG_EXTMEM_BASE + 0x084)
/* EXTMEM_CORE0_DBUS_WR_IC_INT_ENA : R/W ;bitpos:[5] ;default: 1'b0 ; */
/*description: The bit is used to enable interrupt by dbus trying to write icache*/
#define EXTMEM_CORE0_DBUS_WR_IC_INT_ENA (BIT(5))
#define EXTMEM_CORE0_DBUS_WR_IC_INT_ENA_M (BIT(5))
#define EXTMEM_CORE0_DBUS_WR_IC_INT_ENA_V 0x1
#define EXTMEM_CORE0_DBUS_WR_IC_INT_ENA_S 5
/* EXTMEM_CORE0_DBUS_REJECT_INT_ENA : R/W ;bitpos:[4] ;default: 1'b0 ; */
/*description: The bit is used to enable interrupt by authentication fail.*/
#define EXTMEM_CORE0_DBUS_REJECT_INT_ENA (BIT(4))
#define EXTMEM_CORE0_DBUS_REJECT_INT_ENA_M (BIT(4))
#define EXTMEM_CORE0_DBUS_REJECT_INT_ENA_V 0x1
#define EXTMEM_CORE0_DBUS_REJECT_INT_ENA_S 4
/* EXTMEM_CORE0_DBUS_ACS_MSK_IC_INT_ENA : R/W ;bitpos:[3] ;default: 1'b0 ; */
/*description: The bit is used to enable interrupt by cpu access icache while
the corresponding dbus is disabled which include speculative access.*/
#define EXTMEM_CORE0_DBUS_ACS_MSK_IC_INT_ENA (BIT(3))
#define EXTMEM_CORE0_DBUS_ACS_MSK_IC_INT_ENA_M (BIT(3))
#define EXTMEM_CORE0_DBUS_ACS_MSK_IC_INT_ENA_V 0x1
#define EXTMEM_CORE0_DBUS_ACS_MSK_IC_INT_ENA_S 3
/* EXTMEM_CORE0_IBUS_REJECT_INT_ENA : R/W ;bitpos:[2] ;default: 1'b0 ; */
/*description: The bit is used to enable interrupt by authentication fail.*/
#define EXTMEM_CORE0_IBUS_REJECT_INT_ENA (BIT(2))
#define EXTMEM_CORE0_IBUS_REJECT_INT_ENA_M (BIT(2))
#define EXTMEM_CORE0_IBUS_REJECT_INT_ENA_V 0x1
#define EXTMEM_CORE0_IBUS_REJECT_INT_ENA_S 2
/* EXTMEM_CORE0_IBUS_WR_IC_INT_ENA : R/W ;bitpos:[1] ;default: 1'b0 ; */
/*description: The bit is used to enable interrupt by ibus trying to write icache*/
#define EXTMEM_CORE0_IBUS_WR_IC_INT_ENA (BIT(1))
#define EXTMEM_CORE0_IBUS_WR_IC_INT_ENA_M (BIT(1))
#define EXTMEM_CORE0_IBUS_WR_IC_INT_ENA_V 0x1
#define EXTMEM_CORE0_IBUS_WR_IC_INT_ENA_S 1
/* EXTMEM_CORE0_IBUS_ACS_MSK_IC_INT_ENA : R/W ;bitpos:[0] ;default: 1'b0 ; */
/*description: The bit is used to enable interrupt by cpu access icache while
the corresponding ibus is disabled which include speculative access.*/
#define EXTMEM_CORE0_IBUS_ACS_MSK_IC_INT_ENA (BIT(0))
#define EXTMEM_CORE0_IBUS_ACS_MSK_IC_INT_ENA_M (BIT(0))
#define EXTMEM_CORE0_IBUS_ACS_MSK_IC_INT_ENA_V 0x1
#define EXTMEM_CORE0_IBUS_ACS_MSK_IC_INT_ENA_S 0
#define EXTMEM_CORE0_ACS_CACHE_INT_CLR_REG (DR_REG_EXTMEM_BASE + 0x088)
/* EXTMEM_CORE0_DBUS_WR_IC_INT_CLR : WOD ;bitpos:[5] ;default: 1'b0 ; */
/*description: The bit is used to clear interrupt by dbus trying to write icache*/
#define EXTMEM_CORE0_DBUS_WR_IC_INT_CLR (BIT(5))
#define EXTMEM_CORE0_DBUS_WR_IC_INT_CLR_M (BIT(5))
#define EXTMEM_CORE0_DBUS_WR_IC_INT_CLR_V 0x1
#define EXTMEM_CORE0_DBUS_WR_IC_INT_CLR_S 5
/* EXTMEM_CORE0_DBUS_REJECT_INT_CLR : WOD ;bitpos:[4] ;default: 1'b0 ; */
/*description: The bit is used to clear interrupt by authentication fail.*/
#define EXTMEM_CORE0_DBUS_REJECT_INT_CLR (BIT(4))
#define EXTMEM_CORE0_DBUS_REJECT_INT_CLR_M (BIT(4))
#define EXTMEM_CORE0_DBUS_REJECT_INT_CLR_V 0x1
#define EXTMEM_CORE0_DBUS_REJECT_INT_CLR_S 4
/* EXTMEM_CORE0_DBUS_ACS_MSK_IC_INT_CLR : WOD ;bitpos:[3] ;default: 1'b0 ; */
/*description: The bit is used to clear interrupt by cpu access icache while
the corresponding dbus is disabled or icache is disabled which include speculative access.*/
#define EXTMEM_CORE0_DBUS_ACS_MSK_IC_INT_CLR (BIT(3))
#define EXTMEM_CORE0_DBUS_ACS_MSK_IC_INT_CLR_M (BIT(3))
#define EXTMEM_CORE0_DBUS_ACS_MSK_IC_INT_CLR_V 0x1
#define EXTMEM_CORE0_DBUS_ACS_MSK_IC_INT_CLR_S 3
/* EXTMEM_CORE0_IBUS_REJECT_INT_CLR : WOD ;bitpos:[2] ;default: 1'b0 ; */
/*description: The bit is used to clear interrupt by authentication fail.*/
#define EXTMEM_CORE0_IBUS_REJECT_INT_CLR (BIT(2))
#define EXTMEM_CORE0_IBUS_REJECT_INT_CLR_M (BIT(2))
#define EXTMEM_CORE0_IBUS_REJECT_INT_CLR_V 0x1
#define EXTMEM_CORE0_IBUS_REJECT_INT_CLR_S 2
/* EXTMEM_CORE0_IBUS_WR_IC_INT_CLR : WOD ;bitpos:[1] ;default: 1'b0 ; */
/*description: The bit is used to clear interrupt by ibus trying to write icache*/
#define EXTMEM_CORE0_IBUS_WR_IC_INT_CLR (BIT(1))
#define EXTMEM_CORE0_IBUS_WR_IC_INT_CLR_M (BIT(1))
#define EXTMEM_CORE0_IBUS_WR_IC_INT_CLR_V 0x1
#define EXTMEM_CORE0_IBUS_WR_IC_INT_CLR_S 1
/* EXTMEM_CORE0_IBUS_ACS_MSK_IC_INT_CLR : WOD ;bitpos:[0] ;default: 1'b0 ; */
/*description: The bit is used to clear interrupt by cpu access icache while
the corresponding ibus is disabled or icache is disabled which include speculative access.*/
#define EXTMEM_CORE0_IBUS_ACS_MSK_IC_INT_CLR (BIT(0))
#define EXTMEM_CORE0_IBUS_ACS_MSK_IC_INT_CLR_M (BIT(0))
#define EXTMEM_CORE0_IBUS_ACS_MSK_IC_INT_CLR_V 0x1
#define EXTMEM_CORE0_IBUS_ACS_MSK_IC_INT_CLR_S 0
#define EXTMEM_CORE0_ACS_CACHE_INT_ST_REG (DR_REG_EXTMEM_BASE + 0x08C)
/* EXTMEM_CORE0_DBUS_WR_ICACHE_ST : RO ;bitpos:[5] ;default: 1'b0 ; */
/*description: The bit is used to indicate interrupt by dbus trying to write icache*/
#define EXTMEM_CORE0_DBUS_WR_ICACHE_ST (BIT(5))
#define EXTMEM_CORE0_DBUS_WR_ICACHE_ST_M (BIT(5))
#define EXTMEM_CORE0_DBUS_WR_ICACHE_ST_V 0x1
#define EXTMEM_CORE0_DBUS_WR_ICACHE_ST_S 5
/* EXTMEM_CORE0_DBUS_REJECT_ST : RO ;bitpos:[4] ;default: 1'b0 ; */
/*description: The bit is used to indicate interrupt by authentication fail.*/
#define EXTMEM_CORE0_DBUS_REJECT_ST (BIT(4))
#define EXTMEM_CORE0_DBUS_REJECT_ST_M (BIT(4))
#define EXTMEM_CORE0_DBUS_REJECT_ST_V 0x1
#define EXTMEM_CORE0_DBUS_REJECT_ST_S 4
/* EXTMEM_CORE0_DBUS_ACS_MSK_ICACHE_ST : RO ;bitpos:[3] ;default: 1'b0 ; */
/*description: The bit is used to indicate interrupt by cpu access icache while
the core0_dbus is disabled or icache is disabled which include speculative access.*/
#define EXTMEM_CORE0_DBUS_ACS_MSK_ICACHE_ST (BIT(3))
#define EXTMEM_CORE0_DBUS_ACS_MSK_ICACHE_ST_M (BIT(3))
#define EXTMEM_CORE0_DBUS_ACS_MSK_ICACHE_ST_V 0x1
#define EXTMEM_CORE0_DBUS_ACS_MSK_ICACHE_ST_S 3
/* EXTMEM_CORE0_IBUS_REJECT_ST : RO ;bitpos:[2] ;default: 1'b0 ; */
/*description: The bit is used to indicate interrupt by authentication fail.*/
#define EXTMEM_CORE0_IBUS_REJECT_ST (BIT(2))
#define EXTMEM_CORE0_IBUS_REJECT_ST_M (BIT(2))
#define EXTMEM_CORE0_IBUS_REJECT_ST_V 0x1
#define EXTMEM_CORE0_IBUS_REJECT_ST_S 2
/* EXTMEM_CORE0_IBUS_WR_ICACHE_ST : RO ;bitpos:[1] ;default: 1'b0 ; */
/*description: The bit is used to indicate interrupt by ibus trying to write icache*/
#define EXTMEM_CORE0_IBUS_WR_ICACHE_ST (BIT(1))
#define EXTMEM_CORE0_IBUS_WR_ICACHE_ST_M (BIT(1))
#define EXTMEM_CORE0_IBUS_WR_ICACHE_ST_V 0x1
#define EXTMEM_CORE0_IBUS_WR_ICACHE_ST_S 1
/* EXTMEM_CORE0_IBUS_ACS_MSK_ICACHE_ST : RO ;bitpos:[0] ;default: 1'b0 ; */
/*description: The bit is used to indicate interrupt by cpu access icache while
the core0_ibus is disabled or icache is disabled which include speculative access.*/
#define EXTMEM_CORE0_IBUS_ACS_MSK_ICACHE_ST (BIT(0))
#define EXTMEM_CORE0_IBUS_ACS_MSK_ICACHE_ST_M (BIT(0))
#define EXTMEM_CORE0_IBUS_ACS_MSK_ICACHE_ST_V 0x1
#define EXTMEM_CORE0_IBUS_ACS_MSK_ICACHE_ST_S 0
#define EXTMEM_CORE0_DBUS_REJECT_ST_REG (DR_REG_EXTMEM_BASE + 0x090)
/* EXTMEM_CORE0_DBUS_WORLD : RO ;bitpos:[3] ;default: 1'b0 ; */
/*description: The bit is used to indicate the world of CPU access dbus when
authentication fail. 0: WORLD0 1: WORLD1*/
#define EXTMEM_CORE0_DBUS_WORLD (BIT(3))
#define EXTMEM_CORE0_DBUS_WORLD_M (BIT(3))
#define EXTMEM_CORE0_DBUS_WORLD_V 0x1
#define EXTMEM_CORE0_DBUS_WORLD_S 3
/* EXTMEM_CORE0_DBUS_ATTR : RO ;bitpos:[2:0] ;default: 3'b0 ; */
/*description: The bits are used to indicate the attribute of CPU access dbus
when authentication fail. 0: invalidate 1: execute-able 2: read-able 4: write-able.*/
#define EXTMEM_CORE0_DBUS_ATTR 0x00000007
#define EXTMEM_CORE0_DBUS_ATTR_M ((EXTMEM_CORE0_DBUS_ATTR_V)<<(EXTMEM_CORE0_DBUS_ATTR_S))
#define EXTMEM_CORE0_DBUS_ATTR_V 0x7
#define EXTMEM_CORE0_DBUS_ATTR_S 0
#define EXTMEM_CORE0_DBUS_REJECT_VADDR_REG (DR_REG_EXTMEM_BASE + 0x094)
/* EXTMEM_CORE0_DBUS_VADDR : RO ;bitpos:[31:0] ;default: 32'hffffffff ; */
/*description: The bits are used to indicate the virtual address of CPU access
dbus when authentication fail.*/
#define EXTMEM_CORE0_DBUS_VADDR 0xFFFFFFFF
#define EXTMEM_CORE0_DBUS_VADDR_M ((EXTMEM_CORE0_DBUS_VADDR_V)<<(EXTMEM_CORE0_DBUS_VADDR_S))
#define EXTMEM_CORE0_DBUS_VADDR_V 0xFFFFFFFF
#define EXTMEM_CORE0_DBUS_VADDR_S 0
#define EXTMEM_CORE0_IBUS_REJECT_ST_REG (DR_REG_EXTMEM_BASE + 0x098)
/* EXTMEM_CORE0_IBUS_WORLD : RO ;bitpos:[3] ;default: 1'b0 ; */
/*description: The bit is used to indicate the world of CPU access ibus when
authentication fail. 0: WORLD0 1: WORLD1*/
#define EXTMEM_CORE0_IBUS_WORLD (BIT(3))
#define EXTMEM_CORE0_IBUS_WORLD_M (BIT(3))
#define EXTMEM_CORE0_IBUS_WORLD_V 0x1
#define EXTMEM_CORE0_IBUS_WORLD_S 3
/* EXTMEM_CORE0_IBUS_ATTR : RO ;bitpos:[2:0] ;default: 3'b0 ; */
/*description: The bits are used to indicate the attribute of CPU access ibus
when authentication fail. 0: invalidate 1: execute-able 2: read-able*/
#define EXTMEM_CORE0_IBUS_ATTR 0x00000007
#define EXTMEM_CORE0_IBUS_ATTR_M ((EXTMEM_CORE0_IBUS_ATTR_V)<<(EXTMEM_CORE0_IBUS_ATTR_S))
#define EXTMEM_CORE0_IBUS_ATTR_V 0x7
#define EXTMEM_CORE0_IBUS_ATTR_S 0
#define EXTMEM_CORE0_IBUS_REJECT_VADDR_REG (DR_REG_EXTMEM_BASE + 0x09C)
/* EXTMEM_CORE0_IBUS_VADDR : RO ;bitpos:[31:0] ;default: 32'hffffffff ; */
/*description: The bits are used to indicate the virtual address of CPU access
ibus when authentication fail.*/
#define EXTMEM_CORE0_IBUS_VADDR 0xFFFFFFFF
#define EXTMEM_CORE0_IBUS_VADDR_M ((EXTMEM_CORE0_IBUS_VADDR_V)<<(EXTMEM_CORE0_IBUS_VADDR_S))
#define EXTMEM_CORE0_IBUS_VADDR_V 0xFFFFFFFF
#define EXTMEM_CORE0_IBUS_VADDR_S 0
#define EXTMEM_CACHE_MMU_FAULT_CONTENT_REG (DR_REG_EXTMEM_BASE + 0x0A0)
/* EXTMEM_CACHE_MMU_FAULT_CODE : RO ;bitpos:[13:10] ;default: 4'h0 ; */
/*description: The right-most 3 bits are used to indicate the operations which
cause mmu fault occurrence. 0: default 1: cpu miss 2: preload miss 3: writeback 4: cpu miss evict recovery address 5: load miss evict recovery address 6: external dma tx 7: external dma rx. The most significant bit is used to indicate this operation occurs in which one icache.*/
#define EXTMEM_CACHE_MMU_FAULT_CODE 0x0000000F
#define EXTMEM_CACHE_MMU_FAULT_CODE_M ((EXTMEM_CACHE_MMU_FAULT_CODE_V)<<(EXTMEM_CACHE_MMU_FAULT_CODE_S))
#define EXTMEM_CACHE_MMU_FAULT_CODE_V 0xF
#define EXTMEM_CACHE_MMU_FAULT_CODE_S 10
/* EXTMEM_CACHE_MMU_FAULT_CONTENT : RO ;bitpos:[9:0] ;default: 10'h0 ; */
/*description: The bits are used to indicate the content of mmu entry which cause mmu fault..*/
#define EXTMEM_CACHE_MMU_FAULT_CONTENT 0x000003FF
#define EXTMEM_CACHE_MMU_FAULT_CONTENT_M ((EXTMEM_CACHE_MMU_FAULT_CONTENT_V)<<(EXTMEM_CACHE_MMU_FAULT_CONTENT_S))
#define EXTMEM_CACHE_MMU_FAULT_CONTENT_V 0x3FF
#define EXTMEM_CACHE_MMU_FAULT_CONTENT_S 0
#define EXTMEM_CACHE_MMU_FAULT_VADDR_REG (DR_REG_EXTMEM_BASE + 0x0A4)
/* EXTMEM_CACHE_MMU_FAULT_VADDR : RO ;bitpos:[31:0] ;default: 32'h0 ; */
/*description: The bits are used to indicate the virtual address which cause mmu fault..*/
#define EXTMEM_CACHE_MMU_FAULT_VADDR 0xFFFFFFFF
#define EXTMEM_CACHE_MMU_FAULT_VADDR_M ((EXTMEM_CACHE_MMU_FAULT_VADDR_V)<<(EXTMEM_CACHE_MMU_FAULT_VADDR_S))
#define EXTMEM_CACHE_MMU_FAULT_VADDR_V 0xFFFFFFFF
#define EXTMEM_CACHE_MMU_FAULT_VADDR_S 0
#define EXTMEM_CACHE_WRAP_AROUND_CTRL_REG (DR_REG_EXTMEM_BASE + 0x0A8)
/* EXTMEM_CACHE_FLASH_WRAP_AROUND : R/W ;bitpos:[0] ;default: 1'b0 ; */
/*description: The bit is used to enable wrap around mode when read data from flash.*/
#define EXTMEM_CACHE_FLASH_WRAP_AROUND (BIT(0))
#define EXTMEM_CACHE_FLASH_WRAP_AROUND_M (BIT(0))
#define EXTMEM_CACHE_FLASH_WRAP_AROUND_V 0x1
#define EXTMEM_CACHE_FLASH_WRAP_AROUND_S 0
#define EXTMEM_CACHE_MMU_POWER_CTRL_REG (DR_REG_EXTMEM_BASE + 0x0AC)
/* EXTMEM_CACHE_MMU_MEM_FORCE_PU : R/W ;bitpos:[2] ;default: 1'b1 ; */
/*description: The bit is used to power mmu memory down 0: follow_rtc_lslp_pd 1: power up*/
#define EXTMEM_CACHE_MMU_MEM_FORCE_PU (BIT(2))
#define EXTMEM_CACHE_MMU_MEM_FORCE_PU_M (BIT(2))
#define EXTMEM_CACHE_MMU_MEM_FORCE_PU_V 0x1
#define EXTMEM_CACHE_MMU_MEM_FORCE_PU_S 2
/* EXTMEM_CACHE_MMU_MEM_FORCE_PD : R/W ;bitpos:[1] ;default: 1'b0 ; */
/*description: The bit is used to power mmu memory down 0: follow_rtc_lslp_pd 1: power down*/
#define EXTMEM_CACHE_MMU_MEM_FORCE_PD (BIT(1))
#define EXTMEM_CACHE_MMU_MEM_FORCE_PD_M (BIT(1))
#define EXTMEM_CACHE_MMU_MEM_FORCE_PD_V 0x1
#define EXTMEM_CACHE_MMU_MEM_FORCE_PD_S 1
/* EXTMEM_CACHE_MMU_MEM_FORCE_ON : R/W ;bitpos:[0] ;default: 1'b1 ; */
/*description: The bit is used to enable clock gating to save power when access
mmu memory 0: enable 1: disable*/
#define EXTMEM_CACHE_MMU_MEM_FORCE_ON (BIT(0))
#define EXTMEM_CACHE_MMU_MEM_FORCE_ON_M (BIT(0))
#define EXTMEM_CACHE_MMU_MEM_FORCE_ON_V 0x1
#define EXTMEM_CACHE_MMU_MEM_FORCE_ON_S 0
#define EXTMEM_CACHE_STATE_REG (DR_REG_EXTMEM_BASE + 0x0B0)
/* EXTMEM_ICACHE_STATE : RO ;bitpos:[11:0] ;default: 12'h1 ; */
/*description: The bit is used to indicate whether icache main fsm is in idle
state or not. 1: in idle state 0: not in idle state*/
#define EXTMEM_ICACHE_STATE 0x00000FFF
#define EXTMEM_ICACHE_STATE_M ((EXTMEM_ICACHE_STATE_V)<<(EXTMEM_ICACHE_STATE_S))
#define EXTMEM_ICACHE_STATE_V 0xFFF
#define EXTMEM_ICACHE_STATE_S 0
#define EXTMEM_CACHE_ENCRYPT_DECRYPT_RECORD_DISABLE_REG (DR_REG_EXTMEM_BASE + 0x0B4)
/* EXTMEM_RECORD_DISABLE_G0CB_DECRYPT : R/W ;bitpos:[1] ;default: 1'b0 ; */
/*description: Reserved.*/
#define EXTMEM_RECORD_DISABLE_G0CB_DECRYPT (BIT(1))
#define EXTMEM_RECORD_DISABLE_G0CB_DECRYPT_M (BIT(1))
#define EXTMEM_RECORD_DISABLE_G0CB_DECRYPT_V 0x1
#define EXTMEM_RECORD_DISABLE_G0CB_DECRYPT_S 1
/* EXTMEM_RECORD_DISABLE_DB_ENCRYPT : R/W ;bitpos:[0] ;default: 1'b0 ; */
/*description: Reserved.*/
#define EXTMEM_RECORD_DISABLE_DB_ENCRYPT (BIT(0))
#define EXTMEM_RECORD_DISABLE_DB_ENCRYPT_M (BIT(0))
#define EXTMEM_RECORD_DISABLE_DB_ENCRYPT_V 0x1
#define EXTMEM_RECORD_DISABLE_DB_ENCRYPT_S 0
#define EXTMEM_CACHE_ENCRYPT_DECRYPT_CLK_FORCE_ON_REG (DR_REG_EXTMEM_BASE + 0x0B8)
/* EXTMEM_CLK_FORCE_ON_CRYPT : R/W ;bitpos:[2] ;default: 1'b1 ; */
/*description: The bit is used to close clock gating of external memory encrypt
and decrypt clock. 1: close gating 0: open clock gating.*/
#define EXTMEM_CLK_FORCE_ON_CRYPT (BIT(2))
#define EXTMEM_CLK_FORCE_ON_CRYPT_M (BIT(2))
#define EXTMEM_CLK_FORCE_ON_CRYPT_V 0x1
#define EXTMEM_CLK_FORCE_ON_CRYPT_S 2
/* EXTMEM_CLK_FORCE_ON_AUTO_CRYPT : R/W ;bitpos:[1] ;default: 1'b1 ; */
/*description: The bit is used to close clock gating of automatic crypt clock.
1: close gating 0: open clock gating.*/
#define EXTMEM_CLK_FORCE_ON_AUTO_CRYPT (BIT(1))
#define EXTMEM_CLK_FORCE_ON_AUTO_CRYPT_M (BIT(1))
#define EXTMEM_CLK_FORCE_ON_AUTO_CRYPT_V 0x1
#define EXTMEM_CLK_FORCE_ON_AUTO_CRYPT_S 1
/* EXTMEM_CLK_FORCE_ON_MANUAL_CRYPT : R/W ;bitpos:[0] ;default: 1'b1 ; */
/*description: The bit is used to close clock gating of manual crypt clock.
1: close gating 0: open clock gating.*/
#define EXTMEM_CLK_FORCE_ON_MANUAL_CRYPT (BIT(0))
#define EXTMEM_CLK_FORCE_ON_MANUAL_CRYPT_M (BIT(0))
#define EXTMEM_CLK_FORCE_ON_MANUAL_CRYPT_V 0x1
#define EXTMEM_CLK_FORCE_ON_MANUAL_CRYPT_S 0
#define EXTMEM_CACHE_PRELOAD_INT_CTRL_REG (DR_REG_EXTMEM_BASE + 0x0BC)
/* EXTMEM_ICACHE_PRELOAD_INT_CLR : WOD ;bitpos:[2] ;default: 1'b0 ; */
/*description: The bit is used to clear the interrupt by icache pre-load done.*/
#define EXTMEM_ICACHE_PRELOAD_INT_CLR (BIT(2))
#define EXTMEM_ICACHE_PRELOAD_INT_CLR_M (BIT(2))
#define EXTMEM_ICACHE_PRELOAD_INT_CLR_V 0x1
#define EXTMEM_ICACHE_PRELOAD_INT_CLR_S 2
/* EXTMEM_ICACHE_PRELOAD_INT_ENA : R/W ;bitpos:[1] ;default: 1'b0 ; */
/*description: The bit is used to enable the interrupt by icache pre-load done.*/
#define EXTMEM_ICACHE_PRELOAD_INT_ENA (BIT(1))
#define EXTMEM_ICACHE_PRELOAD_INT_ENA_M (BIT(1))
#define EXTMEM_ICACHE_PRELOAD_INT_ENA_V 0x1
#define EXTMEM_ICACHE_PRELOAD_INT_ENA_S 1
/* EXTMEM_ICACHE_PRELOAD_INT_ST : RO ;bitpos:[0] ;default: 1'b0 ; */
/*description: The bit is used to indicate the interrupt by icache pre-load done.*/
#define EXTMEM_ICACHE_PRELOAD_INT_ST (BIT(0))
#define EXTMEM_ICACHE_PRELOAD_INT_ST_M (BIT(0))
#define EXTMEM_ICACHE_PRELOAD_INT_ST_V 0x1
#define EXTMEM_ICACHE_PRELOAD_INT_ST_S 0
#define EXTMEM_CACHE_SYNC_INT_CTRL_REG (DR_REG_EXTMEM_BASE + 0x0C0)
/* EXTMEM_ICACHE_SYNC_INT_CLR : WOD ;bitpos:[2] ;default: 1'b0 ; */
/*description: The bit is used to clear the interrupt by icache sync done.*/
#define EXTMEM_ICACHE_SYNC_INT_CLR (BIT(2))
#define EXTMEM_ICACHE_SYNC_INT_CLR_M (BIT(2))
#define EXTMEM_ICACHE_SYNC_INT_CLR_V 0x1
#define EXTMEM_ICACHE_SYNC_INT_CLR_S 2
/* EXTMEM_ICACHE_SYNC_INT_ENA : R/W ;bitpos:[1] ;default: 1'b0 ; */
/*description: The bit is used to enable the interrupt by icache sync done.*/
#define EXTMEM_ICACHE_SYNC_INT_ENA (BIT(1))
#define EXTMEM_ICACHE_SYNC_INT_ENA_M (BIT(1))
#define EXTMEM_ICACHE_SYNC_INT_ENA_V 0x1
#define EXTMEM_ICACHE_SYNC_INT_ENA_S 1
/* EXTMEM_ICACHE_SYNC_INT_ST : RO ;bitpos:[0] ;default: 1'b0 ; */
/*description: The bit is used to indicate the interrupt by icache sync done.*/
#define EXTMEM_ICACHE_SYNC_INT_ST (BIT(0))
#define EXTMEM_ICACHE_SYNC_INT_ST_M (BIT(0))
#define EXTMEM_ICACHE_SYNC_INT_ST_V 0x1
#define EXTMEM_ICACHE_SYNC_INT_ST_S 0
#define EXTMEM_CACHE_MMU_OWNER_REG (DR_REG_EXTMEM_BASE + 0x0C4)
/* EXTMEM_CACHE_MMU_OWNER : R/W ;bitpos:[3:0] ;default: 4'h0 ; */
/*description: The bits are used to specify the owner of MMU.bit0/bit2: ibus bit1/bit3: dbus*/
#define EXTMEM_CACHE_MMU_OWNER 0x0000000F
#define EXTMEM_CACHE_MMU_OWNER_M ((EXTMEM_CACHE_MMU_OWNER_V)<<(EXTMEM_CACHE_MMU_OWNER_S))
#define EXTMEM_CACHE_MMU_OWNER_V 0xF
#define EXTMEM_CACHE_MMU_OWNER_S 0
#define EXTMEM_CACHE_CONF_MISC_REG (DR_REG_EXTMEM_BASE + 0x0C8)
/* EXTMEM_CACHE_TRACE_ENA : R/W ;bitpos:[2] ;default: 1'b1 ; */
/*description: The bit is used to enable cache trace function.*/
#define EXTMEM_CACHE_TRACE_ENA (BIT(2))
#define EXTMEM_CACHE_TRACE_ENA_M (BIT(2))
#define EXTMEM_CACHE_TRACE_ENA_V 0x1
#define EXTMEM_CACHE_TRACE_ENA_S 2
/* EXTMEM_CACHE_IGNORE_SYNC_MMU_ENTRY_FAULT : R/W ;bitpos:[1] ;default: 1'b1 ; */
/*description: The bit is used to disable checking mmu entry fault by sync operation.*/
#define EXTMEM_CACHE_IGNORE_SYNC_MMU_ENTRY_FAULT (BIT(1))
#define EXTMEM_CACHE_IGNORE_SYNC_MMU_ENTRY_FAULT_M (BIT(1))
#define EXTMEM_CACHE_IGNORE_SYNC_MMU_ENTRY_FAULT_V 0x1
#define EXTMEM_CACHE_IGNORE_SYNC_MMU_ENTRY_FAULT_S 1
/* EXTMEM_CACHE_IGNORE_PRELOAD_MMU_ENTRY_FAULT : R/W ;bitpos:[0] ;default: 1'b1 ; */
/*description: The bit is used to disable checking mmu entry fault by preload operation.*/
#define EXTMEM_CACHE_IGNORE_PRELOAD_MMU_ENTRY_FAULT (BIT(0))
#define EXTMEM_CACHE_IGNORE_PRELOAD_MMU_ENTRY_FAULT_M (BIT(0))
#define EXTMEM_CACHE_IGNORE_PRELOAD_MMU_ENTRY_FAULT_V 0x1
#define EXTMEM_CACHE_IGNORE_PRELOAD_MMU_ENTRY_FAULT_S 0
#define EXTMEM_ICACHE_FREEZE_REG (DR_REG_EXTMEM_BASE + 0x0CC)
/* EXTMEM_ICACHE_FREEZE_DONE : RO ;bitpos:[2] ;default: 1'b0 ; */
/*description: The bit is used to indicate icache freeze success*/
#define EXTMEM_ICACHE_FREEZE_DONE (BIT(2))
#define EXTMEM_ICACHE_FREEZE_DONE_M (BIT(2))
#define EXTMEM_ICACHE_FREEZE_DONE_V 0x1
#define EXTMEM_ICACHE_FREEZE_DONE_S 2
/* EXTMEM_ICACHE_FREEZE_MODE : R/W ;bitpos:[1] ;default: 1'b0 ; */
/*description: The bit is used to configure freeze mode 0: assert busy if
CPU miss 1: assert hit if CPU miss*/
#define EXTMEM_ICACHE_FREEZE_MODE (BIT(1))
#define EXTMEM_ICACHE_FREEZE_MODE_M (BIT(1))
#define EXTMEM_ICACHE_FREEZE_MODE_V 0x1
#define EXTMEM_ICACHE_FREEZE_MODE_S 1
/* EXTMEM_ICACHE_FREEZE_ENA : R/W ;bitpos:[0] ;default: 1'b0 ; */
/*description: The bit is used to enable icache freeze mode*/
#define EXTMEM_ICACHE_FREEZE_ENA (BIT(0))
#define EXTMEM_ICACHE_FREEZE_ENA_M (BIT(0))
#define EXTMEM_ICACHE_FREEZE_ENA_V 0x1
#define EXTMEM_ICACHE_FREEZE_ENA_S 0
#define EXTMEM_ICACHE_ATOMIC_OPERATE_ENA_REG (DR_REG_EXTMEM_BASE + 0x0D0)
/* EXTMEM_ICACHE_ATOMIC_OPERATE_ENA : R/W ;bitpos:[0] ;default: 1'b1 ; */
/*description: The bit is used to activate icache atomic operation protection.
In this case sync/lock operation can not interrupt miss-work. This feature does not work during invalidateAll operation.*/
#define EXTMEM_ICACHE_ATOMIC_OPERATE_ENA (BIT(0))
#define EXTMEM_ICACHE_ATOMIC_OPERATE_ENA_M (BIT(0))
#define EXTMEM_ICACHE_ATOMIC_OPERATE_ENA_V 0x1
#define EXTMEM_ICACHE_ATOMIC_OPERATE_ENA_S 0
#define EXTMEM_CACHE_REQUEST_REG (DR_REG_EXTMEM_BASE + 0x0D4)
/* EXTMEM_CACHE_REQUEST_BYPASS : R/W ;bitpos:[0] ;default: 1'b0 ; */
/*description: The bit is used to disable request recording which could cause performance issue*/
#define EXTMEM_CACHE_REQUEST_BYPASS (BIT(0))
#define EXTMEM_CACHE_REQUEST_BYPASS_M (BIT(0))
#define EXTMEM_CACHE_REQUEST_BYPASS_V 0x1
#define EXTMEM_CACHE_REQUEST_BYPASS_S 0
#define EXTMEM_IBUS_PMS_TBL_LOCK_REG (DR_REG_EXTMEM_BASE + 0x0D8)
/* EXTMEM_IBUS_PMS_LOCK : R/W ;bitpos:[0] ;default: 1'b0 ; */
/*description: The bit is used to configure the ibus permission control section boundary0*/
#define EXTMEM_IBUS_PMS_LOCK (BIT(0))
#define EXTMEM_IBUS_PMS_LOCK_M (BIT(0))
#define EXTMEM_IBUS_PMS_LOCK_V 0x1
#define EXTMEM_IBUS_PMS_LOCK_S 0
#define EXTMEM_IBUS_PMS_TBL_BOUNDARY0_REG (DR_REG_EXTMEM_BASE + 0x0DC)
/* EXTMEM_IBUS_PMS_BOUNDARY0 : R/W ;bitpos:[11:0] ;default: 12'h0 ; */
/*description: The bit is used to configure the ibus permission control section boundary0*/
#define EXTMEM_IBUS_PMS_BOUNDARY0 0x00000FFF
#define EXTMEM_IBUS_PMS_BOUNDARY0_M ((EXTMEM_IBUS_PMS_BOUNDARY0_V)<<(EXTMEM_IBUS_PMS_BOUNDARY0_S))
#define EXTMEM_IBUS_PMS_BOUNDARY0_V 0xFFF
#define EXTMEM_IBUS_PMS_BOUNDARY0_S 0
#define EXTMEM_IBUS_PMS_TBL_BOUNDARY1_REG (DR_REG_EXTMEM_BASE + 0x0E0)
/* EXTMEM_IBUS_PMS_BOUNDARY1 : R/W ;bitpos:[11:0] ;default: 12'h800 ; */
/*description: The bit is used to configure the ibus permission control section boundary1*/
#define EXTMEM_IBUS_PMS_BOUNDARY1 0x00000FFF
#define EXTMEM_IBUS_PMS_BOUNDARY1_M ((EXTMEM_IBUS_PMS_BOUNDARY1_V)<<(EXTMEM_IBUS_PMS_BOUNDARY1_S))
#define EXTMEM_IBUS_PMS_BOUNDARY1_V 0xFFF
#define EXTMEM_IBUS_PMS_BOUNDARY1_S 0
#define EXTMEM_IBUS_PMS_TBL_BOUNDARY2_REG (DR_REG_EXTMEM_BASE + 0x0E4)
/* EXTMEM_IBUS_PMS_BOUNDARY2 : R/W ;bitpos:[11:0] ;default: 12'h800 ; */
/*description: The bit is used to configure the ibus permission control section boundary2*/
#define EXTMEM_IBUS_PMS_BOUNDARY2 0x00000FFF
#define EXTMEM_IBUS_PMS_BOUNDARY2_M ((EXTMEM_IBUS_PMS_BOUNDARY2_V)<<(EXTMEM_IBUS_PMS_BOUNDARY2_S))
#define EXTMEM_IBUS_PMS_BOUNDARY2_V 0xFFF
#define EXTMEM_IBUS_PMS_BOUNDARY2_S 0
#define EXTMEM_IBUS_PMS_TBL_ATTR_REG (DR_REG_EXTMEM_BASE + 0x0E8)
/* EXTMEM_IBUS_PMS_SCT2_ATTR : R/W ;bitpos:[7:4] ;default: 4'hF ; */
/*description: The bit is used to configure attribute of the ibus permission
control section2 bit0: fetch in world0 bit1: load in world0 bit2: fetch in world1 bit3: load in world1*/
#define EXTMEM_IBUS_PMS_SCT2_ATTR 0x0000000F
#define EXTMEM_IBUS_PMS_SCT2_ATTR_M ((EXTMEM_IBUS_PMS_SCT2_ATTR_V)<<(EXTMEM_IBUS_PMS_SCT2_ATTR_S))
#define EXTMEM_IBUS_PMS_SCT2_ATTR_V 0xF
#define EXTMEM_IBUS_PMS_SCT2_ATTR_S 4
/* EXTMEM_IBUS_PMS_SCT1_ATTR : R/W ;bitpos:[3:0] ;default: 4'hF ; */
/*description: The bit is used to configure attribute of the ibus permission
control section1 bit0: fetch in world0 bit1: load in world0 bit2: fetch in world1 bit3: load in world1*/
#define EXTMEM_IBUS_PMS_SCT1_ATTR 0x0000000F
#define EXTMEM_IBUS_PMS_SCT1_ATTR_M ((EXTMEM_IBUS_PMS_SCT1_ATTR_V)<<(EXTMEM_IBUS_PMS_SCT1_ATTR_S))
#define EXTMEM_IBUS_PMS_SCT1_ATTR_V 0xF
#define EXTMEM_IBUS_PMS_SCT1_ATTR_S 0
#define EXTMEM_DBUS_PMS_TBL_LOCK_REG (DR_REG_EXTMEM_BASE + 0x0EC)
/* EXTMEM_DBUS_PMS_LOCK : R/W ;bitpos:[0] ;default: 1'b0 ; */
/*description: The bit is used to configure the ibus permission control section boundary0*/
#define EXTMEM_DBUS_PMS_LOCK (BIT(0))
#define EXTMEM_DBUS_PMS_LOCK_M (BIT(0))
#define EXTMEM_DBUS_PMS_LOCK_V 0x1
#define EXTMEM_DBUS_PMS_LOCK_S 0
#define EXTMEM_DBUS_PMS_TBL_BOUNDARY0_REG (DR_REG_EXTMEM_BASE + 0x0F0)
/* EXTMEM_DBUS_PMS_BOUNDARY0 : R/W ;bitpos:[11:0] ;default: 12'h0 ; */
/*description: The bit is used to configure the dbus permission control section boundary0*/
#define EXTMEM_DBUS_PMS_BOUNDARY0 0x00000FFF
#define EXTMEM_DBUS_PMS_BOUNDARY0_M ((EXTMEM_DBUS_PMS_BOUNDARY0_V)<<(EXTMEM_DBUS_PMS_BOUNDARY0_S))
#define EXTMEM_DBUS_PMS_BOUNDARY0_V 0xFFF
#define EXTMEM_DBUS_PMS_BOUNDARY0_S 0
#define EXTMEM_DBUS_PMS_TBL_BOUNDARY1_REG (DR_REG_EXTMEM_BASE + 0x0F4)
/* EXTMEM_DBUS_PMS_BOUNDARY1 : R/W ;bitpos:[11:0] ;default: 12'h800 ; */
/*description: The bit is used to configure the dbus permission control section boundary1*/
#define EXTMEM_DBUS_PMS_BOUNDARY1 0x00000FFF
#define EXTMEM_DBUS_PMS_BOUNDARY1_M ((EXTMEM_DBUS_PMS_BOUNDARY1_V)<<(EXTMEM_DBUS_PMS_BOUNDARY1_S))
#define EXTMEM_DBUS_PMS_BOUNDARY1_V 0xFFF
#define EXTMEM_DBUS_PMS_BOUNDARY1_S 0
#define EXTMEM_DBUS_PMS_TBL_BOUNDARY2_REG (DR_REG_EXTMEM_BASE + 0x0F8)
/* EXTMEM_DBUS_PMS_BOUNDARY2 : R/W ;bitpos:[11:0] ;default: 12'h800 ; */
/*description: The bit is used to configure the dbus permission control section boundary2*/
#define EXTMEM_DBUS_PMS_BOUNDARY2 0x00000FFF
#define EXTMEM_DBUS_PMS_BOUNDARY2_M ((EXTMEM_DBUS_PMS_BOUNDARY2_V)<<(EXTMEM_DBUS_PMS_BOUNDARY2_S))
#define EXTMEM_DBUS_PMS_BOUNDARY2_V 0xFFF
#define EXTMEM_DBUS_PMS_BOUNDARY2_S 0
#define EXTMEM_DBUS_PMS_TBL_ATTR_REG (DR_REG_EXTMEM_BASE + 0x0FC)
/* EXTMEM_DBUS_PMS_SCT2_ATTR : R/W ;bitpos:[3:2] ;default: 2'd3 ; */
/*description: The bit is used to configure attribute of the dbus permission
control section2 bit0: load in world0 bit2: load in world1*/
#define EXTMEM_DBUS_PMS_SCT2_ATTR 0x00000003
#define EXTMEM_DBUS_PMS_SCT2_ATTR_M ((EXTMEM_DBUS_PMS_SCT2_ATTR_V)<<(EXTMEM_DBUS_PMS_SCT2_ATTR_S))
#define EXTMEM_DBUS_PMS_SCT2_ATTR_V 0x3
#define EXTMEM_DBUS_PMS_SCT2_ATTR_S 2
/* EXTMEM_DBUS_PMS_SCT1_ATTR : R/W ;bitpos:[1:0] ;default: 2'd3 ; */
/*description: The bit is used to configure attribute of the dbus permission
control section1 bit0: load in world0 bit2: load in world1*/
#define EXTMEM_DBUS_PMS_SCT1_ATTR 0x00000003
#define EXTMEM_DBUS_PMS_SCT1_ATTR_M ((EXTMEM_DBUS_PMS_SCT1_ATTR_V)<<(EXTMEM_DBUS_PMS_SCT1_ATTR_S))
#define EXTMEM_DBUS_PMS_SCT1_ATTR_V 0x3
#define EXTMEM_DBUS_PMS_SCT1_ATTR_S 0
#define EXTMEM_CLOCK_GATE_REG (DR_REG_EXTMEM_BASE + 0x100)
/* EXTMEM_CLK_EN : R/W ;bitpos:[0] ;default: 1'b1 ; */
/*description: Reserved.*/
#define EXTMEM_CLK_EN (BIT(0))
#define EXTMEM_CLK_EN_M (BIT(0))
#define EXTMEM_CLK_EN_V 0x1
#define EXTMEM_CLK_EN_S 0
#define EXTMEM_DATE_REG (DR_REG_EXTMEM_BASE + 0x3FC)
/* EXTMEM_DATE : R/W ;bitpos:[27:0] ;default: 28'h2007160 ; */
/*description: Reserved.*/
#define EXTMEM_DATE 0x0FFFFFFF
#define EXTMEM_DATE_M ((EXTMEM_DATE_V)<<(EXTMEM_DATE_S))
#define EXTMEM_DATE_V 0xFFFFFFF
#define EXTMEM_DATE_S 0
#ifdef __cplusplus
}
#endif
#endif /*_SOC_EXTMEM_REG_H_ */

View File

@ -0,0 +1,41 @@
// Copyright 2015-2020 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#pragma once
#include "soc/soc.h"
/* Some of the RF frontend control registers.
* PU/PD fields defined here are used in sleep related functions.
*/
#define FE_GEN_CTRL (DR_REG_FE_BASE + 0x0090)
#define FE_IQ_EST_FORCE_PU (BIT(5))
#define FE_IQ_EST_FORCE_PU_M (BIT(5))
#define FE_IQ_EST_FORCE_PU_V 1
#define FE_IQ_EST_FORCE_PU_S 5
#define FE_IQ_EST_FORCE_PD (BIT(4))
#define FE_IQ_EST_FORCE_PD_M (BIT(4))
#define FE_IQ_EST_FORCE_PD_V 1
#define FE_IQ_EST_FORCE_PD_S 4
#define FE2_TX_INTERP_CTRL (DR_REG_FE2_BASE + 0x00f0)
#define FE2_TX_INF_FORCE_PU (BIT(10))
#define FE2_TX_INF_FORCE_PU_M (BIT(10))
#define FE2_TX_INF_FORCE_PU_V 1
#define FE2_TX_INF_FORCE_PU_S 10
#define FE2_TX_INF_FORCE_PD (BIT(9))
#define FE2_TX_INF_FORCE_PD_M (BIT(9))
#define FE2_TX_INF_FORCE_PD_V 1
#define FE2_TX_INF_FORCE_PD_S 9

View File

@ -0,0 +1,24 @@
// 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
// The following macros have a format SOC_[periph][instance_id] to make it work with `GDMA_MAKE_TRIGGER`
#define SOC_GDMA_TRIG_PERIPH_M2M0 (-1)
#define SOC_GDMA_TRIG_PERIPH_SPI2 (0)
#define SOC_GDMA_TRIG_PERIPH_UART0 (2)
#define SOC_GDMA_TRIG_PERIPH_I2S0 (3)
#define SOC_GDMA_TRIG_PERIPH_AES0 (6)
#define SOC_GDMA_TRIG_PERIPH_SHA0 (7)
#define SOC_GDMA_TRIG_PERIPH_ADC0 (8)

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,331 @@
// 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
typedef volatile struct {
struct {
union {
struct {
uint32_t in_done: 1; /*The raw interrupt bit turns to high level when the last data pointed by one inlink descriptor has been received for Rx channel 0.*/
uint32_t in_suc_eof: 1; /*The raw interrupt bit turns to high level when the last data pointed by one inlink descriptor has been received for Rx channel 0. For UHCI0 the raw interrupt bit turns to high level when the last data pointed by one inlink descriptor has been received and no data error is detected for Rx channel 0.*/
uint32_t in_err_eof: 1; /*The raw interrupt bit turns to high level when data error is detected only in the case that the peripheral is UHCI0 for Rx channel 0. For other peripherals this raw interrupt is reserved.*/
uint32_t out_done: 1; /*The raw interrupt bit turns to high level when the last data pointed by one outlink descriptor has been transmitted to peripherals for Tx channel 0.*/
uint32_t out_eof: 1; /*The raw interrupt bit turns to high level when the last data pointed by one outlink descriptor has been read from memory for Tx channel 0.*/
uint32_t in_dscr_err: 1; /*The raw interrupt bit turns to high level when detecting inlink descriptor error including owner error the second and third word error of inlink descriptor for Rx channel 0.*/
uint32_t out_dscr_err: 1; /*The raw interrupt bit turns to high level when detecting outlink descriptor error including owner error the second and third word error of outlink descriptor for Tx channel 0.*/
uint32_t in_dscr_empty: 1; /*The raw interrupt bit turns to high level when Rx buffer pointed by inlink is full and receiving data is not completed but there is no more inlink for Rx channel 0.*/
uint32_t out_total_eof: 1; /*The raw interrupt bit turns to high level when data corresponding a outlink (includes one link descriptor or few link descriptors) is transmitted out for Tx channel 0.*/
uint32_t infifo_ovf: 1; /*This raw interrupt bit turns to high level when level 1 fifo of Rx channel 0 is overflow.*/
uint32_t infifo_udf: 1; /*This raw interrupt bit turns to high level when level 1 fifo of Rx channel 0 is underflow.*/
uint32_t outfifo_ovf: 1; /*This raw interrupt bit turns to high level when level 1 fifo of Tx channel 0 is overflow.*/
uint32_t outfifo_udf: 1; /*This raw interrupt bit turns to high level when level 1 fifo of Tx channel 0 is underflow.*/
uint32_t reserved13: 19; /*reserved*/
};
uint32_t val;
} raw;
union {
struct {
uint32_t in_done: 1; /*The raw interrupt status bit for the IN_DONE_CH_INT interrupt.*/
uint32_t in_suc_eof: 1; /*The raw interrupt status bit for the IN_SUC_EOF_CH_INT interrupt.*/
uint32_t in_err_eof: 1; /*The raw interrupt status bit for the IN_ERR_EOF_CH_INT interrupt.*/
uint32_t out_done: 1; /*The raw interrupt status bit for the OUT_DONE_CH_INT interrupt.*/
uint32_t out_eof: 1; /*The raw interrupt status bit for the OUT_EOF_CH_INT interrupt.*/
uint32_t in_dscr_err: 1; /*The raw interrupt status bit for the IN_DSCR_ERR_CH_INT interrupt.*/
uint32_t out_dscr_err: 1; /*The raw interrupt status bit for the OUT_DSCR_ERR_CH_INT interrupt.*/
uint32_t in_dscr_empty: 1; /*The raw interrupt status bit for the IN_DSCR_EMPTY_CH_INT interrupt.*/
uint32_t out_total_eof: 1; /*The raw interrupt status bit for the OUT_TOTAL_EOF_CH_INT interrupt.*/
uint32_t infifo_ovf: 1; /*The raw interrupt status bit for the INFIFO_OVF_L1_CH_INT interrupt.*/
uint32_t infifo_udf: 1; /*The raw interrupt status bit for the INFIFO_UDF_L1_CH_INT interrupt.*/
uint32_t outfifo_ovf: 1; /*The raw interrupt status bit for the OUTFIFO_OVF_L1_CH_INT interrupt.*/
uint32_t outfifo_udf: 1; /*The raw interrupt status bit for the OUTFIFO_UDF_L1_CH_INT interrupt.*/
uint32_t reserved13: 19; /*reserved*/
};
uint32_t val;
} st;
union {
struct {
uint32_t in_done: 1; /*The interrupt enable bit for the IN_DONE_CH_INT interrupt.*/
uint32_t in_suc_eof: 1; /*The interrupt enable bit for the IN_SUC_EOF_CH_INT interrupt.*/
uint32_t in_err_eof: 1; /*The interrupt enable bit for the IN_ERR_EOF_CH_INT interrupt.*/
uint32_t out_done: 1; /*The interrupt enable bit for the OUT_DONE_CH_INT interrupt.*/
uint32_t out_eof: 1; /*The interrupt enable bit for the OUT_EOF_CH_INT interrupt.*/
uint32_t in_dscr_err: 1; /*The interrupt enable bit for the IN_DSCR_ERR_CH_INT interrupt.*/
uint32_t out_dscr_err: 1; /*The interrupt enable bit for the OUT_DSCR_ERR_CH_INT interrupt.*/
uint32_t in_dscr_empty: 1; /*The interrupt enable bit for the IN_DSCR_EMPTY_CH_INT interrupt.*/
uint32_t out_total_eof: 1; /*The interrupt enable bit for the OUT_TOTAL_EOF_CH_INT interrupt.*/
uint32_t infifo_ovf: 1; /*The interrupt enable bit for the INFIFO_OVF_L1_CH_INT interrupt.*/
uint32_t infifo_udf: 1; /*The interrupt enable bit for the INFIFO_UDF_L1_CH_INT interrupt.*/
uint32_t outfifo_ovf: 1; /*The interrupt enable bit for the OUTFIFO_OVF_L1_CH_INT interrupt.*/
uint32_t outfifo_udf: 1; /*The interrupt enable bit for the OUTFIFO_UDF_L1_CH_INT interrupt.*/
uint32_t reserved13: 19; /*reserved*/
};
uint32_t val;
} ena;
union {
struct {
uint32_t in_done: 1; /*Set this bit to clear the IN_DONE_CH_INT interrupt.*/
uint32_t in_suc_eof: 1; /*Set this bit to clear the IN_SUC_EOF_CH_INT interrupt.*/
uint32_t in_err_eof: 1; /*Set this bit to clear the IN_ERR_EOF_CH_INT interrupt.*/
uint32_t out_done: 1; /*Set this bit to clear the OUT_DONE_CH_INT interrupt.*/
uint32_t out_eof: 1; /*Set this bit to clear the OUT_EOF_CH_INT interrupt.*/
uint32_t in_dscr_err: 1; /*Set this bit to clear the IN_DSCR_ERR_CH_INT interrupt.*/
uint32_t out_dscr_err: 1; /*Set this bit to clear the OUT_DSCR_ERR_CH_INT interrupt.*/
uint32_t in_dscr_empty: 1; /*Set this bit to clear the IN_DSCR_EMPTY_CH_INT interrupt.*/
uint32_t out_total_eof: 1; /*Set this bit to clear the OUT_TOTAL_EOF_CH_INT interrupt.*/
uint32_t infifo_ovf: 1; /*Set this bit to clear the INFIFO_OVF_L1_CH_INT interrupt.*/
uint32_t infifo_udf: 1; /*Set this bit to clear the INFIFO_UDF_L1_CH_INT interrupt.*/
uint32_t outfifo_ovf: 1; /*Set this bit to clear the OUTFIFO_OVF_L1_CH_INT interrupt.*/
uint32_t outfifo_udf: 1; /*Set this bit to clear the OUTFIFO_UDF_L1_CH_INT interrupt.*/
uint32_t reserved13: 19; /*reserved*/
};
uint32_t val;
} clr;
} intr[3];
uint32_t reserved_30;
uint32_t reserved_34;
uint32_t reserved_38;
uint32_t reserved_3c;
union {
struct {
uint32_t ahb_testmode: 3; /*reserved*/
uint32_t reserved3: 1; /*reserved*/
uint32_t ahb_testaddr: 2; /*reserved*/
uint32_t reserved6: 26; /*reserved*/
};
uint32_t val;
} ahb_test;
union {
struct {
uint32_t ahbm_rst_inter: 1; /*Set this bit then clear this bit to reset the internal ahb FSM.*/
uint32_t reserved1: 1;
uint32_t arb_pri_dis: 1; /*Set this bit to disable priority arbitration function.*/
uint32_t clk_en: 1;
uint32_t reserved4: 28;
};
uint32_t val;
} misc_conf;
uint32_t date; /**/
uint32_t reserved_4c;
uint32_t reserved_50;
uint32_t reserved_54;
uint32_t reserved_58;
uint32_t reserved_5c;
uint32_t reserved_60;
uint32_t reserved_64;
uint32_t reserved_68;
uint32_t reserved_6c;
struct {
struct {
union {
struct {
uint32_t in_rst: 1; /*This bit is used to reset DMA channel 0 Rx FSM and Rx FIFO pointer.*/
uint32_t in_loop_test: 1; /*reserved*/
uint32_t indscr_burst_en: 1; /*Set this bit to 1 to enable INCR burst transfer for Rx channel 0 reading link descriptor when accessing internal SRAM.*/
uint32_t in_data_burst_en: 1; /*Set this bit to 1 to enable INCR burst transfer for Rx channel 0 receiving data when accessing internal SRAM.*/
uint32_t mem_trans_en: 1; /*Set this bit 1 to enable automatic transmitting data from memory to memory via DMA.*/
uint32_t reserved5: 27; /*reserved*/
};
uint32_t val;
} in_conf0;
union {
struct {
uint32_t reserved0: 12;
uint32_t in_check_owner: 1; /*Set this bit to enable checking the owner attribute of the link descriptor.*/
uint32_t reserved13: 19; /*reserved*/
};
uint32_t val;
} in_conf1;
union {
struct {
uint32_t infifo_full: 1; /*L1 Rx FIFO full signal for Rx channel 0.*/
uint32_t infifo_empty: 1; /*L1 Rx FIFO empty signal for Rx channel 0.*/
uint32_t infifo_cnt: 6; /*The register stores the byte number of the data in L1 Rx FIFO for Rx channel 0.*/
uint32_t reserved8: 15; /*reserved*/
uint32_t in_remain_under_1b: 1; /*reserved*/
uint32_t in_remain_under_2b: 1; /*reserved*/
uint32_t in_remain_under_3b: 1; /*reserved*/
uint32_t in_remain_under_4b: 1; /*reserved*/
uint32_t in_buf_hungry: 1; /*reserved*/
uint32_t reserved28: 4; /*reserved*/
};
uint32_t val;
} infifo_status;
union {
struct {
uint32_t infifo_rdata: 12; /*This register stores the data popping from DMA FIFO.*/
uint32_t infifo_pop: 1; /*Set this bit to pop data from DMA FIFO.*/
uint32_t reserved13: 19; /*reserved*/
};
uint32_t val;
} in_pop;
union {
struct {
uint32_t addr: 20; /*This register stores the 20 least significant bits of the first inlink descriptor's address.*/
uint32_t auto_ret: 1; /*Set this bit to return to current inlink descriptor's address when there are some errors in current receiving data.*/
uint32_t stop: 1; /*Set this bit to stop dealing with the inlink descriptors.*/
uint32_t start: 1; /*Set this bit to start dealing with the inlink descriptors.*/
uint32_t restart: 1; /*Set this bit to mount a new inlink descriptor.*/
uint32_t park: 1; /*1: the inlink descriptor's FSM is in idle state. 0: the inlink descriptor's FSM is working.*/
uint32_t reserved25: 7;
};
uint32_t val;
} in_link;
union {
struct {
uint32_t inlink_dscr_addr: 18; /*This register stores the current inlink descriptor's address.*/
uint32_t in_dscr_state: 2; /*reserved*/
uint32_t in_state: 3; /*reserved*/
uint32_t reserved23: 9; /*reserved*/
};
uint32_t val;
} in_state;
uint32_t in_suc_eof_des_addr; /**/
uint32_t in_err_eof_des_addr; /**/
uint32_t in_dscr; /**/
uint32_t in_dscr_bf0; /**/
uint32_t in_dscr_bf1; /**/
union {
struct {
uint32_t rx_pri: 4; /*The priority of Rx channel 0. The larger of the value the higher of the priority.*/
uint32_t reserved4: 28;
};
uint32_t val;
} in_pri;
union {
struct {
uint32_t sel: 6; /*This register is used to select peripheral for Rx channel 0. 0:SPI2. 1: reserved. 2: UHCI0. 3: I2S0. 4: reserved. 5: reserved. 6: AES. 7: SHA. 8: ADC_DAC.*/
uint32_t reserved6: 26;
};
uint32_t val;
} in_peri_sel;
} in;
uint32_t reserved_a4;
uint32_t reserved_a8;
uint32_t reserved_ac;
uint32_t reserved_b0;
uint32_t reserved_b4;
uint32_t reserved_b8;
uint32_t reserved_bc;
uint32_t reserved_c0;
uint32_t reserved_c4;
uint32_t reserved_c8;
uint32_t reserved_cc;
struct {
union {
struct {
uint32_t out_rst: 1; /*This bit is used to reset DMA channel 0 Tx FSM and Tx FIFO pointer.*/
uint32_t out_loop_test: 1; /*reserved*/
uint32_t out_auto_wrback: 1; /*Set this bit to enable automatic outlink-writeback when all the data in tx buffer has been transmitted.*/
uint32_t out_eof_mode: 1; /*EOF flag generation mode when transmitting data. 1: EOF flag for Tx channel 0 is generated when data need to transmit has been popped from FIFO in DMA*/
uint32_t outdscr_burst_en: 1; /*Set this bit to 1 to enable INCR burst transfer for Tx channel 0 reading link descriptor when accessing internal SRAM.*/
uint32_t out_data_burst_en: 1; /*Set this bit to 1 to enable INCR burst transfer for Tx channel 0 transmitting data when accessing internal SRAM.*/
uint32_t reserved6: 26;
};
uint32_t val;
} out_conf0;
union {
struct {
uint32_t reserved0: 12;
uint32_t out_check_owner: 1; /*Set this bit to enable checking the owner attribute of the link descriptor.*/
uint32_t reserved13: 19; /*reserved*/
};
uint32_t val;
} out_conf1;
union {
struct {
uint32_t outfifo_full: 1; /*L1 Tx FIFO full signal for Tx channel 0.*/
uint32_t outfifo_empty: 1; /*L1 Tx FIFO empty signal for Tx channel 0.*/
uint32_t outfifo_cnt: 6; /*The register stores the byte number of the data in L1 Tx FIFO for Tx channel 0.*/
uint32_t reserved8: 15; /*reserved*/
uint32_t out_remain_under_1b: 1; /*reserved*/
uint32_t out_remain_under_2b: 1; /*reserved*/
uint32_t out_remain_under_3b: 1; /*reserved*/
uint32_t out_remain_under_4b: 1; /*reserved*/
uint32_t reserved27: 5; /*reserved*/
};
uint32_t val;
} outfifo_status;
union {
struct {
uint32_t outfifo_wdata: 9; /*This register stores the data that need to be pushed into DMA FIFO.*/
uint32_t outfifo_push: 1; /*Set this bit to push data into DMA FIFO.*/
uint32_t reserved10: 22; /*reserved*/
};
uint32_t val;
} out_push;
union {
struct {
uint32_t addr: 20; /*This register stores the 20 least significant bits of the first outlink descriptor's address.*/
uint32_t stop: 1; /*Set this bit to stop dealing with the outlink descriptors.*/
uint32_t start: 1; /*Set this bit to start dealing with the outlink descriptors.*/
uint32_t restart: 1; /*Set this bit to restart a new outlink from the last address.*/
uint32_t park: 1; /*1: the outlink descriptor's FSM is in idle state. 0: the outlink descriptor's FSM is working.*/
uint32_t reserved24: 8;
};
uint32_t val;
} out_link;
union {
struct {
uint32_t outlink_dscr_addr: 18; /*This register stores the current outlink descriptor's address.*/
uint32_t out_dscr_state: 2; /*reserved*/
uint32_t out_state: 3; /*reserved*/
uint32_t reserved23: 9; /*reserved*/
};
uint32_t val;
} out_state;
uint32_t out_eof_des_addr; /**/
uint32_t out_eof_bfr_des_addr; /**/
uint32_t out_dscr; /**/
uint32_t out_dscr_bf0; /**/
uint32_t out_dscr_bf1; /**/
union {
struct {
uint32_t tx_pri: 4; /*The priority of Tx channel 0. The larger of the value the higher of the priority.*/
uint32_t reserved4: 28;
};
uint32_t val;
} out_pri;
union {
struct {
uint32_t sel: 6; /*This register is used to select peripheral for Tx channel 0. 0:SPI2. 1: reserved. 2: UHCI0. 3: I2S0. 4: reserved. 5: reserved. 6: AES. 7: SHA. 8: ADC_DAC.*/
uint32_t reserved6: 26;
};
uint32_t val;
} out_peri_sel;
} out;
uint32_t reserved_104;
uint32_t reserved_108;
uint32_t reserved_10c;
uint32_t reserved_110;
uint32_t reserved_114;
uint32_t reserved_118;
uint32_t reserved_11c;
uint32_t reserved_120;
uint32_t reserved_124;
uint32_t reserved_128;
uint32_t reserved_12c;
} channel[3];
} gdma_dev_t;
extern gdma_dev_t GDMA;
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,27 @@
// 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
#define GPIO_MATRIX_CONST_ONE_INPUT (0x1E)
#define GPIO_MATRIX_CONST_ZERO_INPUT (0x1F)
#ifdef __cplusplus
}
#endif

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,114 @@
// 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.
#ifndef _SOC_GPIO_SD_REG_H_
#define _SOC_GPIO_SD_REG_H_
#ifdef __cplusplus
extern "C" {
#endif
#include "soc.h"
#define GPIO_SIGMADELTA0_REG (DR_REG_GPIO_SD_BASE + 0x0000)
/* GPIO_SD0_PRESCALE : R/W ;bitpos:[15:8] ;default: 8'hff ; */
/*description: */
#define GPIO_SD0_PRESCALE 0x000000FF
#define GPIO_SD0_PRESCALE_M ((GPIO_SD0_PRESCALE_V)<<(GPIO_SD0_PRESCALE_S))
#define GPIO_SD0_PRESCALE_V 0xFF
#define GPIO_SD0_PRESCALE_S 8
/* GPIO_SD0_IN : R/W ;bitpos:[7:0] ;default: 8'h0 ; */
/*description: */
#define GPIO_SD0_IN 0x000000FF
#define GPIO_SD0_IN_M ((GPIO_SD0_IN_V)<<(GPIO_SD0_IN_S))
#define GPIO_SD0_IN_V 0xFF
#define GPIO_SD0_IN_S 0
#define GPIO_SIGMADELTA1_REG (DR_REG_GPIO_SD_BASE + 0x0004)
/* GPIO_SD1_PRESCALE : R/W ;bitpos:[15:8] ;default: 8'hff ; */
/*description: */
#define GPIO_SD1_PRESCALE 0x000000FF
#define GPIO_SD1_PRESCALE_M ((GPIO_SD1_PRESCALE_V)<<(GPIO_SD1_PRESCALE_S))
#define GPIO_SD1_PRESCALE_V 0xFF
#define GPIO_SD1_PRESCALE_S 8
/* GPIO_SD1_IN : R/W ;bitpos:[7:0] ;default: 8'h0 ; */
/*description: */
#define GPIO_SD1_IN 0x000000FF
#define GPIO_SD1_IN_M ((GPIO_SD1_IN_V)<<(GPIO_SD1_IN_S))
#define GPIO_SD1_IN_V 0xFF
#define GPIO_SD1_IN_S 0
#define GPIO_SIGMADELTA2_REG (DR_REG_GPIO_SD_BASE + 0x0008)
/* GPIO_SD2_PRESCALE : R/W ;bitpos:[15:8] ;default: 8'hff ; */
/*description: */
#define GPIO_SD2_PRESCALE 0x000000FF
#define GPIO_SD2_PRESCALE_M ((GPIO_SD2_PRESCALE_V)<<(GPIO_SD2_PRESCALE_S))
#define GPIO_SD2_PRESCALE_V 0xFF
#define GPIO_SD2_PRESCALE_S 8
/* GPIO_SD2_IN : R/W ;bitpos:[7:0] ;default: 8'h0 ; */
/*description: */
#define GPIO_SD2_IN 0x000000FF
#define GPIO_SD2_IN_M ((GPIO_SD2_IN_V)<<(GPIO_SD2_IN_S))
#define GPIO_SD2_IN_V 0xFF
#define GPIO_SD2_IN_S 0
#define GPIO_SIGMADELTA3_REG (DR_REG_GPIO_SD_BASE + 0x000c)
/* GPIO_SD3_PRESCALE : R/W ;bitpos:[15:8] ;default: 8'hff ; */
/*description: */
#define GPIO_SD3_PRESCALE 0x000000FF
#define GPIO_SD3_PRESCALE_M ((GPIO_SD3_PRESCALE_V)<<(GPIO_SD3_PRESCALE_S))
#define GPIO_SD3_PRESCALE_V 0xFF
#define GPIO_SD3_PRESCALE_S 8
/* GPIO_SD3_IN : R/W ;bitpos:[7:0] ;default: 8'h0 ; */
/*description: */
#define GPIO_SD3_IN 0x000000FF
#define GPIO_SD3_IN_M ((GPIO_SD3_IN_V)<<(GPIO_SD3_IN_S))
#define GPIO_SD3_IN_V 0xFF
#define GPIO_SD3_IN_S 0
#define GPIO_SIGMADELTA_CG_REG (DR_REG_GPIO_SD_BASE + 0x0020)
/* GPIO_SD_CLK_EN : R/W ;bitpos:[31] ;default: 1'h0 ; */
/*description: */
#define GPIO_SD_CLK_EN (BIT(31))
#define GPIO_SD_CLK_EN_M (BIT(31))
#define GPIO_SD_CLK_EN_V 0x1
#define GPIO_SD_CLK_EN_S 31
#define GPIO_SIGMADELTA_MISC_REG (DR_REG_GPIO_SD_BASE + 0x0024)
/* GPIO_SPI_SWAP : R/W ;bitpos:[31] ;default: 1'h0 ; */
/*description: */
#define GPIO_SPI_SWAP (BIT(31))
#define GPIO_SPI_SWAP_M (BIT(31))
#define GPIO_SPI_SWAP_V 0x1
#define GPIO_SPI_SWAP_S 31
/* GPIO_FUNCTION_CLK_EN : R/W ;bitpos:[30] ;default: 1'd0 ; */
/*description: */
#define GPIO_FUNCTION_CLK_EN (BIT(30))
#define GPIO_FUNCTION_CLK_EN_M (BIT(30))
#define GPIO_FUNCTION_CLK_EN_V 0x1
#define GPIO_FUNCTION_CLK_EN_S 30
#define GPIO_SIGMADELTA_VERSION_REG (DR_REG_GPIO_SD_BASE + 0x0028)
/* GPIO_SD_DATE : R/W ;bitpos:[27:0] ;default: 28'h2006230 ; */
/*description: */
#define GPIO_SD_DATE 0x0FFFFFFF
#define GPIO_SD_DATE_M ((GPIO_SD_DATE_V)<<(GPIO_SD_DATE_S))
#define GPIO_SD_DATE_V 0xFFFFFFF
#define GPIO_SD_DATE_S 0
#ifdef __cplusplus
}
#endif
#endif /*_SOC_GPIO_SD_REG_H_ */

View File

@ -0,0 +1,61 @@
// 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.
#ifndef _SOC_GPIO_SD_STRUCT_H_
#define _SOC_GPIO_SD_STRUCT_H_
#ifdef __cplusplus
extern "C" {
#endif
typedef volatile struct {
union {
struct {
uint32_t duty: 8;
uint32_t prescale: 8;
uint32_t reserved16: 16;
};
uint32_t val;
} channel[4];
uint32_t reserved_10;
uint32_t reserved_14;
uint32_t reserved_18;
uint32_t reserved_1c;
union {
struct {
uint32_t reserved0: 31;
uint32_t clk_en: 1;
};
uint32_t val;
} cg;
union {
struct {
uint32_t reserved0: 30;
uint32_t function_clk_en: 1;
uint32_t spi_swap: 1;
};
uint32_t val;
} misc;
union {
struct {
uint32_t date: 28;
uint32_t reserved28: 4;
};
uint32_t val;
} version;
} gpio_sd_dev_t;
extern gpio_sd_dev_t SIGMADELTA;
#ifdef __cplusplus
}
#endif
#endif /* _SOC_GPIO_SD_STRUCT_H_ */

View File

@ -0,0 +1,184 @@
// 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.
#ifndef _SOC_GPIO_SIG_MAP_H_
#define _SOC_GPIO_SIG_MAP_H_
#define SPICLK_OUT_MUX_IDX SPICLK_OUT_IDX
#define SPIQ_IN_IDX 0
#define SPIQ_OUT_IDX 0
#define SPID_IN_IDX 1
#define SPID_OUT_IDX 1
#define SPIHD_IN_IDX 2
#define SPIHD_OUT_IDX 2
#define SPIWP_IN_IDX 3
#define SPIWP_OUT_IDX 3
#define SPICLK_OUT_IDX 4
#define SPICS0_OUT_IDX 5
#define U0RXD_IN_IDX 6
#define U0TXD_OUT_IDX 6
#define U0CTS_IN_IDX 7
#define U0RTS_OUT_IDX 7
#define U0DSR_IN_IDX 8
#define U0DTR_OUT_IDX 8
#define U1RXD_IN_IDX 9
#define U1TXD_OUT_IDX 9
#define U1CTS_IN_IDX 10
#define U1RTS_OUT_IDX 10
#define U1DSR_IN_IDX 11
#define U1DTR_OUT_IDX 11
#define I2S_MCLK_IN_IDX 12
#define I2S_MCLK_OUT_IDX 12
#define I2SO_BCK_IN_IDX 13
#define I2SO_BCK_OUT_IDX 13
#define I2SO_WS_IN_IDX 14
#define I2SO_WS_OUT_IDX 14
#define I2SI_SD_IN_IDX 15
#define I2SO_SD_OUT_IDX 15
#define I2SI_BCK_IN_IDX 16
#define I2SI_BCK_OUT_IDX 16
#define I2SI_WS_IN_IDX 17
#define I2SI_WS_OUT_IDX 17
#define GPIO_BT_PRIORITY_IDX 18
#define GPIO_WLAN_PRIO_IDX 18
#define GPIO_BT_ACTIVE_IDX 19
#define GPIO_WLAN_ACTIVE_IDX 19
#define BB_DIAG0_IDX 20
#define BB_DIAG1_IDX 21
#define BB_DIAG2_IDX 22
#define BB_DIAG3_IDX 23
#define BB_DIAG4_IDX 24
#define BB_DIAG5_IDX 25
#define BB_DIAG6_IDX 26
#define BB_DIAG7_IDX 27
#define BB_DIAG8_IDX 28
#define BB_DIAG9_IDX 29
#define BB_DIAG10_IDX 30
#define BB_DIAG11_IDX 31
#define BB_DIAG12_IDX 32
#define BB_DIAG13_IDX 33
#define BB_DIAG14_IDX 34
#define BB_DIAG15_IDX 35
#define BB_DIAG16_IDX 36
#define BB_DIAG17_IDX 37
#define BB_DIAG18_IDX 38
#define BB_DIAG19_IDX 39
#define USB_EXTPHY_VP_IDX 40
#define USB_EXTPHY_OEN_IDX 40
#define USB_EXTPHY_VM_IDX 41
#define USB_EXTPHY_SPEED_IDX 41
#define USB_EXTPHY_RCV_IDX 42
#define USB_EXTPHY_VPO_IDX 42
#define USB_EXTPHY_VMO_IDX 43
#define USB_EXTPHY_SUSPND_IDX 44
#define EXT_ADC_START_IDX 45
#define LEDC_LS_SIG_OUT0_IDX 45
#define LEDC_LS_SIG_OUT1_IDX 46
#define LEDC_LS_SIG_OUT2_IDX 47
#define LEDC_LS_SIG_OUT3_IDX 48
#define LEDC_LS_SIG_OUT4_IDX 49
#define LEDC_LS_SIG_OUT5_IDX 50
#define RMT_SIG_IN0_IDX 51
#define RMT_SIG_OUT0_IDX 51
#define RMT_SIG_IN1_IDX 52
#define RMT_SIG_OUT1_IDX 52
#define I2CEXT0_SCL_IN_IDX 53
#define I2CEXT0_SCL_OUT_IDX 53
#define I2CEXT0_SDA_IN_IDX 54
#define I2CEXT0_SDA_OUT_IDX 54
#define GPIO_SD0_OUT_IDX 55
#define GPIO_SD1_OUT_IDX 56
#define GPIO_SD2_OUT_IDX 57
#define GPIO_SD3_OUT_IDX 58
#define FSPICLK_IN_IDX 63
#define FSPICLK_OUT_IDX 63
#define FSPIQ_IN_IDX 64
#define FSPIQ_OUT_IDX 64
#define FSPID_IN_IDX 65
#define FSPID_OUT_IDX 65
#define FSPIHD_IN_IDX 66
#define FSPIHD_OUT_IDX 66
#define FSPIWP_IN_IDX 67
#define FSPIWP_OUT_IDX 67
#define FSPICS0_IN_IDX 68
#define FSPICS0_OUT_IDX 68
#define FSPICS1_OUT_IDX 69
#define FSPICS2_OUT_IDX 70
#define FSPICS3_OUT_IDX 71
#define FSPICS4_OUT_IDX 72
#define FSPICS5_OUT_IDX 73
#define TWAI_RX_IDX 74
#define TWAI_TX_IDX 74
#define TWAI_BUS_OFF_ON_IDX 75
#define TWAI_CLKOUT_IDX 76
#define PCMFSYNC_IN_IDX 77
#define BT_AUDIO0_IRQ_IDX 77
#define PCMCLK_IN_IDX 78
#define BT_AUDIO1_IRQ_IDX 78
#define PCMDIN_IDX 79
#define BT_AUDIO2_IRQ_IDX 79
#define RW_WAKEUP_REQ_IDX 80
#define BLE_AUDIO0_IRQ_IDX 80
#define BLE_AUDIO1_IRQ_IDX 81
#define BLE_AUDIO2_IRQ_IDX 82
#define PCMFSYNC_OUT_IDX 83
#define PCMCLK_OUT_IDX 84
#define PCMDOUT_IDX 85
#define BLE_AUDIO_SYNC0_P_IDX 86
#define BLE_AUDIO_SYNC1_P_IDX 87
#define BLE_AUDIO_SYNC2_P_IDX 88
#define ANT_SEL0_IDX 89
#define ANT_SEL1_IDX 90
#define ANT_SEL2_IDX 91
#define ANT_SEL3_IDX 92
#define ANT_SEL4_IDX 93
#define ANT_SEL5_IDX 94
#define ANT_SEL6_IDX 95
#define ANT_SEL7_IDX 96
#define SIG_IN_FUNC_97_IDX 97
#define SIG_IN_FUNC97_IDX 97
#define SIG_IN_FUNC_98_IDX 98
#define SIG_IN_FUNC98_IDX 98
#define SIG_IN_FUNC_99_IDX 99
#define SIG_IN_FUNC99_IDX 99
#define SIG_IN_FUNC_100_IDX 100
#define SIG_IN_FUNC100_IDX 100
#define SYNCERR_IDX 101
#define SYNCFOUND_FLAG_IDX 102
#define EVT_CNTL_IMMEDIATE_ABORT_IDX 103
#define LINKLBL_IDX 104
#define DATA_EN_IDX 105
#define DATA_IDX 106
#define PKT_TX_ON_IDX 107
#define PKT_RX_ON_IDX 108
#define RW_TX_ON_IDX 109
#define RW_RX_ON_IDX 110
#define EVT_REQ_P_IDX 111
#define EVT_STOP_P_IDX 112
#define BT_MODE_ON_IDX 113
#define GPIO_LC_DIAG0_IDX 114
#define GPIO_LC_DIAG1_IDX 115
#define GPIO_LC_DIAG2_IDX 116
#define CH_IDX_IDX 117
#define RX_WINDOW_IDX 118
#define UPDATE_RX_IDX 119
#define RX_STATUS_IDX 120
#define CLK_GPIO_IDX 121
#define NBT_BLE_IDX 122
#define CLK_OUT_OUT1_IDX 123
#define CLK_OUT_OUT2_IDX 124
#define CLK_OUT_OUT3_IDX 125
#define SPICS1_OUT_IDX 126
#define SIG_GPIO_OUT_IDX 128
#define GPIO_MAP_DATE_IDX 0x2006130
#endif /* _SOC_GPIO_SIG_MAP_H_ */

View File

@ -0,0 +1,437 @@
// 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.
#ifndef _SOC_GPIO_STRUCT_H_
#define _SOC_GPIO_STRUCT_H_
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
typedef volatile struct {
uint32_t bt_select; /**/
union {
struct {
uint32_t data: 26;
uint32_t reserved26: 6;
};
uint32_t val;
} out;
union {
struct {
uint32_t out_w1ts: 26;
uint32_t reserved26: 6;
};
uint32_t val;
} out_w1ts;
union {
struct {
uint32_t out_w1tc: 26;
uint32_t reserved26: 6;
};
uint32_t val;
} out_w1tc;
uint32_t reserved_10;
uint32_t reserved_14;
uint32_t reserved_18;
union {
struct {
uint32_t sel: 8;
uint32_t reserved8: 24;
};
uint32_t val;
} sdio_select;
union {
struct {
uint32_t data: 26;
uint32_t reserved26: 6;
};
uint32_t val;
} enable;
union {
struct {
uint32_t enable_w1ts:26;
uint32_t reserved26: 6;
};
uint32_t val;
} enable_w1ts;
union {
struct {
uint32_t enable_w1tc:26;
uint32_t reserved26: 6;
};
uint32_t val;
} enable_w1tc;
uint32_t reserved_2c;
uint32_t reserved_30;
uint32_t reserved_34;
union {
struct {
uint32_t strapping: 16;
uint32_t reserved16:16;
};
uint32_t val;
} strap;
union {
struct {
uint32_t data: 26;
uint32_t reserved26: 6;
};
uint32_t val;
} in;
uint32_t reserved_40;
union {
struct {
uint32_t intr_st: 26;
uint32_t reserved26: 6;
};
uint32_t val;
} status;
union {
struct {
uint32_t status_w1ts:26;
uint32_t reserved26: 6;
};
uint32_t val;
} status_w1ts;
union {
struct {
uint32_t status_w1tc:26;
uint32_t reserved26: 6;
};
uint32_t val;
} status_w1tc;
uint32_t reserved_50;
uint32_t reserved_54;
uint32_t reserved_58;
union {
struct {
uint32_t intr: 26;
uint32_t reserved26: 6;
};
uint32_t val;
} pcpu_int;
union {
struct {
uint32_t intr: 26;
uint32_t reserved26: 6;
};
uint32_t val;
} pcpu_nmi_int;
union {
struct {
uint32_t intr: 26;
uint32_t reserved26: 6;
};
uint32_t val;
} cpusdio_int;
uint32_t reserved_68;
uint32_t reserved_6c;
uint32_t reserved_70;
union {
struct {
uint32_t sync2_bypass: 2;
uint32_t pad_driver: 1;
uint32_t sync1_bypass: 2;
uint32_t reserved5: 2;
uint32_t int_type: 3;
uint32_t wakeup_enable: 1;
uint32_t config: 2;
uint32_t int_ena: 5;
uint32_t reserved18: 14;
};
uint32_t val;
} pin[26];
uint32_t reserved_dc;
uint32_t reserved_e0;
uint32_t reserved_e4;
uint32_t reserved_e8;
uint32_t reserved_ec;
uint32_t reserved_f0;
uint32_t reserved_f4;
uint32_t reserved_f8;
uint32_t reserved_fc;
uint32_t reserved_100;
uint32_t reserved_104;
uint32_t reserved_108;
uint32_t reserved_10c;
uint32_t reserved_110;
uint32_t reserved_114;
uint32_t reserved_118;
uint32_t reserved_11c;
uint32_t reserved_120;
uint32_t reserved_124;
uint32_t reserved_128;
uint32_t reserved_12c;
uint32_t reserved_130;
uint32_t reserved_134;
uint32_t reserved_138;
uint32_t reserved_13c;
uint32_t reserved_140;
uint32_t reserved_144;
uint32_t reserved_148;
union {
struct {
uint32_t intr_st_next: 26;
uint32_t reserved26: 6;
};
uint32_t val;
} status_next;
uint32_t reserved_150;
union {
struct {
uint32_t func_sel: 5;
uint32_t sig_in_inv: 1;
uint32_t sig_in_sel: 1;
uint32_t reserved7: 25;
};
uint32_t val;
} func_in_sel_cfg[128];
uint32_t reserved_354;
uint32_t reserved_358;
uint32_t reserved_35c;
uint32_t reserved_360;
uint32_t reserved_364;
uint32_t reserved_368;
uint32_t reserved_36c;
uint32_t reserved_370;
uint32_t reserved_374;
uint32_t reserved_378;
uint32_t reserved_37c;
uint32_t reserved_380;
uint32_t reserved_384;
uint32_t reserved_388;
uint32_t reserved_38c;
uint32_t reserved_390;
uint32_t reserved_394;
uint32_t reserved_398;
uint32_t reserved_39c;
uint32_t reserved_3a0;
uint32_t reserved_3a4;
uint32_t reserved_3a8;
uint32_t reserved_3ac;
uint32_t reserved_3b0;
uint32_t reserved_3b4;
uint32_t reserved_3b8;
uint32_t reserved_3bc;
uint32_t reserved_3c0;
uint32_t reserved_3c4;
uint32_t reserved_3c8;
uint32_t reserved_3cc;
uint32_t reserved_3d0;
uint32_t reserved_3d4;
uint32_t reserved_3d8;
uint32_t reserved_3dc;
uint32_t reserved_3e0;
uint32_t reserved_3e4;
uint32_t reserved_3e8;
uint32_t reserved_3ec;
uint32_t reserved_3f0;
uint32_t reserved_3f4;
uint32_t reserved_3f8;
uint32_t reserved_3fc;
uint32_t reserved_400;
uint32_t reserved_404;
uint32_t reserved_408;
uint32_t reserved_40c;
uint32_t reserved_410;
uint32_t reserved_414;
uint32_t reserved_418;
uint32_t reserved_41c;
uint32_t reserved_420;
uint32_t reserved_424;
uint32_t reserved_428;
uint32_t reserved_42c;
uint32_t reserved_430;
uint32_t reserved_434;
uint32_t reserved_438;
uint32_t reserved_43c;
uint32_t reserved_440;
uint32_t reserved_444;
uint32_t reserved_448;
uint32_t reserved_44c;
uint32_t reserved_450;
uint32_t reserved_454;
uint32_t reserved_458;
uint32_t reserved_45c;
uint32_t reserved_460;
uint32_t reserved_464;
uint32_t reserved_468;
uint32_t reserved_46c;
uint32_t reserved_470;
uint32_t reserved_474;
uint32_t reserved_478;
uint32_t reserved_47c;
uint32_t reserved_480;
uint32_t reserved_484;
uint32_t reserved_488;
uint32_t reserved_48c;
uint32_t reserved_490;
uint32_t reserved_494;
uint32_t reserved_498;
uint32_t reserved_49c;
uint32_t reserved_4a0;
uint32_t reserved_4a4;
uint32_t reserved_4a8;
uint32_t reserved_4ac;
uint32_t reserved_4b0;
uint32_t reserved_4b4;
uint32_t reserved_4b8;
uint32_t reserved_4bc;
uint32_t reserved_4c0;
uint32_t reserved_4c4;
uint32_t reserved_4c8;
uint32_t reserved_4cc;
uint32_t reserved_4d0;
uint32_t reserved_4d4;
uint32_t reserved_4d8;
uint32_t reserved_4dc;
uint32_t reserved_4e0;
uint32_t reserved_4e4;
uint32_t reserved_4e8;
uint32_t reserved_4ec;
uint32_t reserved_4f0;
uint32_t reserved_4f4;
uint32_t reserved_4f8;
uint32_t reserved_4fc;
uint32_t reserved_500;
uint32_t reserved_504;
uint32_t reserved_508;
uint32_t reserved_50c;
uint32_t reserved_510;
uint32_t reserved_514;
uint32_t reserved_518;
uint32_t reserved_51c;
uint32_t reserved_520;
uint32_t reserved_524;
uint32_t reserved_528;
uint32_t reserved_52c;
uint32_t reserved_530;
uint32_t reserved_534;
uint32_t reserved_538;
uint32_t reserved_53c;
uint32_t reserved_540;
uint32_t reserved_544;
uint32_t reserved_548;
uint32_t reserved_54c;
uint32_t reserved_550;
union {
struct {
uint32_t func_sel: 8;
uint32_t inv_sel: 1;
uint32_t oen_sel: 1;
uint32_t oen_inv_sel: 1;
uint32_t reserved11: 21;
};
uint32_t val;
} func_out_sel_cfg[26];
uint32_t reserved_5bc;
uint32_t reserved_5c0;
uint32_t reserved_5c4;
uint32_t reserved_5c8;
uint32_t reserved_5cc;
uint32_t reserved_5d0;
uint32_t reserved_5d4;
uint32_t reserved_5d8;
uint32_t reserved_5dc;
uint32_t reserved_5e0;
uint32_t reserved_5e4;
uint32_t reserved_5e8;
uint32_t reserved_5ec;
uint32_t reserved_5f0;
uint32_t reserved_5f4;
uint32_t reserved_5f8;
uint32_t reserved_5fc;
uint32_t reserved_600;
uint32_t reserved_604;
uint32_t reserved_608;
uint32_t reserved_60c;
uint32_t reserved_610;
uint32_t reserved_614;
uint32_t reserved_618;
uint32_t reserved_61c;
uint32_t reserved_620;
uint32_t reserved_624;
uint32_t reserved_628;
union {
struct {
uint32_t clk_en: 1;
uint32_t reserved1: 31;
};
uint32_t val;
} clock_gate;
uint32_t reserved_630;
uint32_t reserved_634;
uint32_t reserved_638;
uint32_t reserved_63c;
uint32_t reserved_640;
uint32_t reserved_644;
uint32_t reserved_648;
uint32_t reserved_64c;
uint32_t reserved_650;
uint32_t reserved_654;
uint32_t reserved_658;
uint32_t reserved_65c;
uint32_t reserved_660;
uint32_t reserved_664;
uint32_t reserved_668;
uint32_t reserved_66c;
uint32_t reserved_670;
uint32_t reserved_674;
uint32_t reserved_678;
uint32_t reserved_67c;
uint32_t reserved_680;
uint32_t reserved_684;
uint32_t reserved_688;
uint32_t reserved_68c;
uint32_t reserved_690;
uint32_t reserved_694;
uint32_t reserved_698;
uint32_t reserved_69c;
uint32_t reserved_6a0;
uint32_t reserved_6a4;
uint32_t reserved_6a8;
uint32_t reserved_6ac;
uint32_t reserved_6b0;
uint32_t reserved_6b4;
uint32_t reserved_6b8;
uint32_t reserved_6bc;
uint32_t reserved_6c0;
uint32_t reserved_6c4;
uint32_t reserved_6c8;
uint32_t reserved_6cc;
uint32_t reserved_6d0;
uint32_t reserved_6d4;
uint32_t reserved_6d8;
uint32_t reserved_6dc;
uint32_t reserved_6e0;
uint32_t reserved_6e4;
uint32_t reserved_6e8;
uint32_t reserved_6ec;
uint32_t reserved_6f0;
uint32_t reserved_6f4;
uint32_t reserved_6f8;
union {
struct {
uint32_t date: 28;
uint32_t reserved28: 4;
};
uint32_t val;
} date;
} gpio_dev_t;
extern gpio_dev_t GPIO;
#ifdef __cplusplus
}
#endif
#endif /* _SOC_GPIO_STRUCT_H_ */

Some files were not shown because too many files have changed in this diff Show More