mirror of
https://github.com/espressif/esp-idf.git
synced 2025-08-05 05:34:32 +02:00
Merge branch 'feature/mcpwm_test_iram_safe' into 'master'
driver-ng: test with CONFIG_COMPILER_OPTIMIZATION_NONE=y See merge request espressif/esp-idf!19283
This commit is contained in:
@@ -177,9 +177,8 @@ esp_err_t mcpwm_new_soft_fault(const mcpwm_soft_fault_config_t *config, mcpwm_fa
|
||||
return ESP_OK;
|
||||
|
||||
err:
|
||||
if (soft_fault) {
|
||||
// soft_fault must be NULL in the error handling path, and it's a determined behaviour to free a NULL pointer in esp-idf
|
||||
free(soft_fault);
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
@@ -252,9 +252,8 @@ esp_err_t mcpwm_new_soft_sync_src(const mcpwm_soft_sync_config_t *config, mcpwm_
|
||||
return ESP_OK;
|
||||
|
||||
err:
|
||||
if (soft_sync) {
|
||||
// soft_sync must be NULL in the error handling path, and it's a determined behaviour to free a NULL pointer in esp-idf
|
||||
free(soft_sync);
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
@@ -46,6 +46,7 @@ static esp_err_t rmt_bytes_encoder_reset(rmt_encoder_t *encoder)
|
||||
return ESP_OK;
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline uint8_t _bitwise_reverse(uint8_t n)
|
||||
{
|
||||
n = ((n & 0xf0) >> 4) | ((n & 0x0f) << 4);
|
||||
|
@@ -1,4 +1,7 @@
|
||||
CONFIG_COMPILER_DUMP_RTL_FILES=y
|
||||
CONFIG_GPIO_CTRL_FUNC_IN_IRAM=y
|
||||
CONFIG_COMPILER_OPTIMIZATION_NONE=y
|
||||
# silent the error check, as the error string are stored in rodata, causing RTL check failure
|
||||
CONFIG_COMPILER_OPTIMIZATION_CHECKS_SILENT=y
|
||||
# GPIO test uses IPC call, the default stack size of IPC task can satisfy the -O0 optimization
|
||||
CONFIG_ESP_IPC_TASK_STACK_SIZE=2048
|
||||
|
@@ -1,5 +1,6 @@
|
||||
CONFIG_COMPILER_DUMP_RTL_FILES=y
|
||||
CONFIG_GPTIMER_CTRL_FUNC_IN_IRAM=y
|
||||
CONFIG_GPTIMER_ISR_IRAM_SAFE=y
|
||||
CONFIG_COMPILER_OPTIMIZATION_NONE=y
|
||||
# silent the error check, as the error string are stored in rodata, causing RTL check failure
|
||||
CONFIG_COMPILER_OPTIMIZATION_CHECKS_SILENT=y
|
||||
|
@@ -1,5 +1,5 @@
|
||||
CONFIG_COMPILER_DUMP_RTL_FILES=y
|
||||
CONFIG_I2S_ISR_IRAM_SAFE=y
|
||||
|
||||
CONFIG_COMPILER_OPTIMIZATION_NONE=y
|
||||
# silent the error check, as the error string are stored in rodata, causing RTL check failure
|
||||
CONFIG_COMPILER_OPTIMIZATION_CHECKS_SILENT=y
|
||||
|
@@ -3,7 +3,6 @@ CONFIG_FREERTOS_USE_TICKLESS_IDLE=y
|
||||
CONFIG_COMPILER_OPTIMIZATION_SIZE=y
|
||||
CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_SIZE=y
|
||||
CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_SILENT=y
|
||||
CONFIG_I2S_ISR_IRAM_SAFE=y
|
||||
CONFIG_COMPILER_DUMP_RTL_FILES=y
|
||||
# silent the error check, as the error string are stored in rodata, causing RTL check failure
|
||||
CONFIG_COMPILER_OPTIMIZATION_CHECKS_SILENT=y
|
||||
|
@@ -8,6 +8,10 @@ set(srcs "test_app_main.c"
|
||||
"test_mcpwm_timer.c"
|
||||
"test_mcpwm_utils.c")
|
||||
|
||||
if(CONFIG_MCPWM_ISR_IRAM_SAFE)
|
||||
list(APPEND srcs "test_mcpwm_iram.c")
|
||||
endif()
|
||||
|
||||
# In order for the cases defined by `TEST_CASE` to be linked into the final elf,
|
||||
# the component can be registered as WHOLE_ARCHIVE
|
||||
idf_component_register(SRCS ${srcs}
|
||||
|
90
components/driver/test_apps/mcpwm/main/test_mcpwm_iram.c
Normal file
90
components/driver/test_apps/mcpwm/main/test_mcpwm_iram.c
Normal file
@@ -0,0 +1,90 @@
|
||||
/*
|
||||
* SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
#include <stdio.h>
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
#include "freertos/event_groups.h"
|
||||
#include "unity.h"
|
||||
#include "soc/soc_caps.h"
|
||||
#include "esp_private/esp_clk.h"
|
||||
#include "esp_private/spi_flash_os.h"
|
||||
#include "driver/mcpwm_cap.h"
|
||||
#include "driver/mcpwm_sync.h"
|
||||
#include "driver/gpio.h"
|
||||
#include "test_mcpwm_utils.h"
|
||||
|
||||
static bool IRAM_ATTR test_capture_callback_iram_safe(mcpwm_cap_channel_handle_t cap_channel, const mcpwm_capture_event_data_t *edata, void *user_data)
|
||||
{
|
||||
uint32_t *cap_value = (uint32_t *)user_data;
|
||||
if (edata->cap_edge == MCPWM_CAP_EDGE_NEG) {
|
||||
cap_value[1] = edata->cap_value;
|
||||
} else {
|
||||
cap_value[0] = edata->cap_value;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
static void IRAM_ATTR test_mcpwm_capture_gpio_simulate(int gpio_sig)
|
||||
{
|
||||
// disable flash cache
|
||||
spi_flash_guard_get()->start();
|
||||
gpio_set_level(gpio_sig, 1);
|
||||
esp_rom_delay_us(1000);
|
||||
gpio_set_level(gpio_sig, 0);
|
||||
// enable flash cache
|
||||
spi_flash_guard_get()->end();
|
||||
}
|
||||
|
||||
TEST_CASE("mcpwm_capture_iram_safe", "[mcpwm]")
|
||||
{
|
||||
printf("install mcpwm capture timer\r\n");
|
||||
mcpwm_cap_timer_handle_t cap_timer = NULL;
|
||||
mcpwm_capture_timer_config_t cap_timer_config = {
|
||||
.clk_src = MCPWM_CAPTURE_CLK_SRC_APB,
|
||||
.group_id = 0,
|
||||
};
|
||||
TEST_ESP_OK(mcpwm_new_capture_timer(&cap_timer_config, &cap_timer));
|
||||
|
||||
const int cap_gpio = 0;
|
||||
// put the GPIO into a preset state
|
||||
gpio_set_level(cap_gpio, 0);
|
||||
|
||||
printf("install mcpwm capture channel\r\n");
|
||||
mcpwm_cap_channel_handle_t pps_channel;
|
||||
mcpwm_capture_channel_config_t cap_chan_config = {
|
||||
.gpio_num = cap_gpio,
|
||||
.prescale = 1,
|
||||
.flags.pos_edge = true,
|
||||
.flags.neg_edge = true,
|
||||
.flags.io_loop_back = true, // so we can use GPIO functions to simulate the external capture signal
|
||||
.flags.pull_up = true,
|
||||
};
|
||||
TEST_ESP_OK(mcpwm_new_capture_channel(cap_timer, &cap_chan_config, &pps_channel));
|
||||
|
||||
printf("install callback for capture channel\r\n");
|
||||
mcpwm_capture_event_callbacks_t cbs = {
|
||||
.on_cap = test_capture_callback_iram_safe,
|
||||
};
|
||||
uint32_t cap_value[2] = {0};
|
||||
TEST_ESP_OK(mcpwm_capture_channel_register_event_callbacks(pps_channel, &cbs, cap_value));
|
||||
|
||||
printf("enable and start capture timer\r\n");
|
||||
TEST_ESP_OK(mcpwm_capture_timer_enable(cap_timer));
|
||||
TEST_ESP_OK(mcpwm_capture_timer_start(cap_timer));
|
||||
|
||||
printf("disable cache, simulate GPIO capture signal\r\n");
|
||||
test_mcpwm_capture_gpio_simulate(cap_gpio);
|
||||
|
||||
printf("capture value: Pos=%u, Neg=%u\r\n", cap_value[0], cap_value[1]);
|
||||
// Capture timer is clocked from APB by default
|
||||
uint32_t clk_src_res = esp_clk_apb_freq();
|
||||
TEST_ASSERT_UINT_WITHIN(2000, clk_src_res / 1000, cap_value[1] - cap_value[0]);
|
||||
|
||||
printf("uninstall capture channel and timer\r\n");
|
||||
TEST_ESP_OK(mcpwm_del_capture_channel(pps_channel));
|
||||
TEST_ESP_OK(mcpwm_capture_timer_disable(cap_timer));
|
||||
TEST_ESP_OK(mcpwm_del_capture_timer(cap_timer));
|
||||
}
|
@@ -1,5 +1,6 @@
|
||||
CONFIG_COMPILER_DUMP_RTL_FILES=y
|
||||
CONFIG_MCPWM_ISR_IRAM_SAFE=y
|
||||
|
||||
CONFIG_GPIO_CTRL_FUNC_IN_IRAM=y
|
||||
CONFIG_COMPILER_OPTIMIZATION_NONE=y
|
||||
# silent the error check, as the error string are stored in rodata, causing RTL check failure
|
||||
CONFIG_COMPILER_OPTIMIZATION_CHECKS_SILENT=y
|
||||
|
@@ -2,6 +2,6 @@ CONFIG_COMPILER_DUMP_RTL_FILES=y
|
||||
CONFIG_PCNT_CTRL_FUNC_IN_IRAM=y
|
||||
CONFIG_PCNT_ISR_IRAM_SAFE=y
|
||||
CONFIG_GPIO_CTRL_FUNC_IN_IRAM=y
|
||||
|
||||
CONFIG_COMPILER_OPTIMIZATION_NONE=y
|
||||
# silent the error check, as the error string are stored in rodata, causing RTL check failure
|
||||
CONFIG_COMPILER_OPTIMIZATION_CHECKS_SILENT=y
|
||||
|
@@ -1,6 +1,6 @@
|
||||
CONFIG_COMPILER_DUMP_RTL_FILES=y
|
||||
CONFIG_RMT_ISR_IRAM_SAFE=y
|
||||
|
||||
CONFIG_COMPILER_OPTIMIZATION_NONE=y
|
||||
# silent the error check, as the error string are stored in rodata, causing RTL check failure
|
||||
CONFIG_COMPILER_OPTIMIZATION_CHECKS_SILENT=y
|
||||
CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_SILENT=y
|
||||
|
@@ -1,5 +1,5 @@
|
||||
CONFIG_COMPILER_DUMP_RTL_FILES=y
|
||||
CONFIG_SDM_CTRL_FUNC_IN_IRAM=y
|
||||
|
||||
CONFIG_COMPILER_OPTIMIZATION_NONE=y
|
||||
# silent the error check, as the error string are stored in rodata, causing RTL check failure
|
||||
CONFIG_COMPILER_OPTIMIZATION_CHECKS_SILENT=y
|
||||
|
@@ -2,5 +2,8 @@ CONFIG_COMPILER_DUMP_RTL_FILES=y
|
||||
CONFIG_ADC_ONESHOT_CTRL_FUNC_IN_IRAM=y
|
||||
CONFIG_GPTIMER_ISR_IRAM_SAFE=y
|
||||
CONFIG_ADC_CONTINUOUS_ISR_IRAM_SAFE=y
|
||||
CONFIG_COMPILER_OPTIMIZATION_NONE=y
|
||||
# silent the error check, as the error string are stored in rodata, causing RTL check failure
|
||||
CONFIG_COMPILER_OPTIMIZATION_CHECKS_SILENT=y
|
||||
CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_SILENT=y
|
||||
CONFIG_HAL_ASSERTION_SILENT=y
|
||||
|
@@ -33,8 +33,9 @@ static void rtc_clk_cpu_freq_to_8m(void);
|
||||
|
||||
void rtc_clk_32k_enable_external(void)
|
||||
{
|
||||
gpio_ll_input_enable(&GPIO, EXT_OSC_SLOW_GPIO_NUM);
|
||||
gpio_ll_hold_en(&GPIO, EXT_OSC_SLOW_GPIO_NUM);
|
||||
// EXT_OSC_SLOW_GPIO_NUM == GPIO_NUM_0
|
||||
PIN_INPUT_ENABLE(IO_MUX_GPIO0_REG);
|
||||
REG_SET_BIT(RTC_CNTL_PAD_HOLD_REG, BIT(EXT_OSC_SLOW_GPIO_NUM));
|
||||
}
|
||||
|
||||
void rtc_clk_8m_enable(bool clk_8m_en, bool d256_en)
|
||||
|
@@ -1,5 +1,5 @@
|
||||
CONFIG_COMPILER_DUMP_RTL_FILES=y
|
||||
CONFIG_LCD_RGB_ISR_IRAM_SAFE=y
|
||||
|
||||
CONFIG_COMPILER_OPTIMIZATION_NONE=y
|
||||
# silent the error check, as the error string are stored in rodata, causing RTL check failure
|
||||
CONFIG_COMPILER_OPTIMIZATION_CHECKS_SILENT=y
|
||||
|
@@ -519,6 +519,7 @@ static inline void adc_oneshot_ll_set_atten(adc_unit_t adc_n, adc_channel_t chan
|
||||
* @param channel ADCn channel number.
|
||||
* @return atten The attenuation option.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline adc_atten_t adc_ll_get_atten(adc_unit_t adc_n, adc_channel_t channel)
|
||||
{
|
||||
if (adc_n == ADC_UNIT_1) {
|
||||
@@ -578,6 +579,7 @@ static inline void adc_ll_set_power_manage(adc_ll_power_t manage)
|
||||
* @param adc_n ADC unit.
|
||||
* @param ctrl ADC controller.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_set_controller(adc_unit_t adc_n, adc_ll_controller_t ctrl)
|
||||
{
|
||||
if (adc_n == ADC_UNIT_1) {
|
||||
|
@@ -225,6 +225,7 @@ static inline void gpio_ll_set_intr_type(gpio_dev_t *hw, uint32_t gpio_num, gpio
|
||||
* @param core_id interrupt core id
|
||||
* @param status interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_get_intr_status(gpio_dev_t *hw, uint32_t core_id, uint32_t *status)
|
||||
{
|
||||
*status = (core_id == 0) ? hw->pcpu_int : hw->acpu_int;
|
||||
@@ -237,6 +238,7 @@ static inline void gpio_ll_get_intr_status(gpio_dev_t *hw, uint32_t core_id, uin
|
||||
* @param core_id interrupt core id
|
||||
* @param status interrupt status high
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_get_intr_status_high(gpio_dev_t *hw, uint32_t core_id, uint32_t *status)
|
||||
{
|
||||
*status = (core_id == 0) ? HAL_FORCE_READ_U32_REG_FIELD(hw->pcpu_int1, intr) : HAL_FORCE_READ_U32_REG_FIELD(hw->acpu_int1, intr);
|
||||
@@ -248,6 +250,7 @@ static inline void gpio_ll_get_intr_status_high(gpio_dev_t *hw, uint32_t core_id
|
||||
* @param hw Peripheral GPIO hardware instance address.
|
||||
* @param mask interrupt status clear mask
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_clear_intr_status(gpio_dev_t *hw, uint32_t mask)
|
||||
{
|
||||
hw->status_w1tc = mask;
|
||||
@@ -259,6 +262,7 @@ static inline void gpio_ll_clear_intr_status(gpio_dev_t *hw, uint32_t mask)
|
||||
* @param hw Peripheral GPIO hardware instance address.
|
||||
* @param mask interrupt status high clear mask
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_clear_intr_status_high(gpio_dev_t *hw, uint32_t mask)
|
||||
{
|
||||
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->status1_w1tc, intr_st, mask);
|
||||
@@ -271,6 +275,7 @@ static inline void gpio_ll_clear_intr_status_high(gpio_dev_t *hw, uint32_t mask)
|
||||
* @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);
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_intr_enable_on_core(gpio_dev_t *hw, uint32_t core_id, uint32_t gpio_num)
|
||||
{
|
||||
if (core_id == 0) {
|
||||
@@ -286,6 +291,7 @@ static inline void gpio_ll_intr_enable_on_core(gpio_dev_t *hw, uint32_t core_id,
|
||||
* @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);
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_intr_disable(gpio_dev_t *hw, uint32_t gpio_num)
|
||||
{
|
||||
hw->pin[gpio_num].int_ena = 0; //disable GPIO intr
|
||||
@@ -420,6 +426,7 @@ static inline void gpio_ll_od_enable(gpio_dev_t *hw, uint32_t gpio_num)
|
||||
* @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
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_set_level(gpio_dev_t *hw, uint32_t gpio_num, uint32_t level)
|
||||
{
|
||||
if (level) {
|
||||
|
@@ -446,6 +446,7 @@ static inline volatile void *i2s_ll_get_intr_status_reg(i2s_dev_t *hw)
|
||||
* @return
|
||||
* - module interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t i2s_ll_get_intr_status(i2s_dev_t *hw)
|
||||
{
|
||||
return hw->int_st.val;
|
||||
@@ -465,6 +466,7 @@ static inline volatile void *i2s_ll_get_interrupt_status_reg(i2s_dev_t *hw)
|
||||
* @param hw Peripheral I2S hardware instance address.
|
||||
* @param clr_mask Interrupt mask to clear interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void i2s_ll_clear_intr_status(i2s_dev_t *hw, uint32_t clr_mask)
|
||||
{
|
||||
hw->int_clr.val = clr_mask;
|
||||
@@ -603,6 +605,7 @@ static inline void i2s_ll_rx_stop_link(i2s_dev_t *hw)
|
||||
* @param hw Peripheral I2S hardware instance address.
|
||||
* @param eof_addr Pointer to accept out eof des address
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void i2s_ll_tx_get_eof_des_addr(i2s_dev_t *hw, uint32_t *eof_addr)
|
||||
{
|
||||
*eof_addr = hw->out_eof_des_addr;
|
||||
@@ -614,6 +617,7 @@ static inline void i2s_ll_tx_get_eof_des_addr(i2s_dev_t *hw, uint32_t *eof_addr)
|
||||
* @param hw Peripheral I2S hardware instance address.
|
||||
* @param eof_addr Pointer to accept in eof des address
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void i2s_ll_rx_get_eof_des_addr(i2s_dev_t *hw, uint32_t *eof_addr)
|
||||
{
|
||||
*eof_addr = hw->in_eof_des_addr;
|
||||
|
@@ -89,6 +89,7 @@ static inline void pcnt_ll_set_level_action(pcnt_dev_t *hw, uint32_t unit, uint3
|
||||
* @param unit Pulse Counter unit number
|
||||
* @return PCNT count value (a signed integer)
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline int pcnt_ll_get_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
{
|
||||
typeof(hw->cnt_unit[unit]) cnt_reg = hw->cnt_unit[unit];
|
||||
@@ -102,6 +103,7 @@ static inline int pcnt_ll_get_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
* @param hw Peripheral PCNT hardware instance address.
|
||||
* @param unit PCNT unit number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void pcnt_ll_stop_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
{
|
||||
hw->ctrl.val |= 1 << (2 * unit + 1);
|
||||
@@ -113,6 +115,7 @@ static inline void pcnt_ll_stop_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
* @param hw Peripheral PCNT hardware instance address.
|
||||
* @param unit PCNT unit number, select from uint32_t
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void pcnt_ll_start_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
{
|
||||
hw->ctrl.val &= ~(1 << (2 * unit + 1));
|
||||
@@ -124,6 +127,7 @@ static inline void pcnt_ll_start_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
* @param hw Peripheral PCNT hardware instance address.
|
||||
* @param unit PCNT unit number, select from uint32_t
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void pcnt_ll_clear_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
{
|
||||
hw->ctrl.val |= 1 << (2 * unit);
|
||||
|
@@ -139,6 +139,7 @@ static inline void rmt_ll_tx_set_channel_clock_div(rmt_dev_t *dev, uint32_t chan
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT TX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_reset_pointer(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
dev->conf_ch[channel].conf1.mem_rd_rst = 1;
|
||||
@@ -153,6 +154,7 @@ static inline void rmt_ll_tx_reset_pointer(rmt_dev_t *dev, uint32_t channel)
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT TX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_start(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
dev->conf_ch[channel].conf1.tx_start = 1;
|
||||
@@ -189,6 +191,7 @@ static inline void rmt_ll_tx_enable_wrap(rmt_dev_t *dev, uint32_t channel, bool
|
||||
* @param channel RMT TX channel number
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_enable_loop(rmt_dev_t *dev, uint32_t channel, bool enable)
|
||||
{
|
||||
dev->conf_ch[channel].conf1.tx_conti_mode = enable;
|
||||
@@ -202,6 +205,7 @@ static inline void rmt_ll_tx_enable_loop(rmt_dev_t *dev, uint32_t channel, bool
|
||||
* @param level IDLE level (1 => high, 0 => low)
|
||||
* @param enable True to fix the IDLE level, otherwise the IDLE level is determined by EOF encoder
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_fix_idle_level(rmt_dev_t *dev, uint32_t channel, uint8_t level, bool enable)
|
||||
{
|
||||
dev->conf_ch[channel].conf1.idle_out_en = enable;
|
||||
@@ -306,6 +310,7 @@ static inline void rmt_ll_rx_set_channel_clock_div(rmt_dev_t *dev, uint32_t chan
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT RX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_rx_reset_pointer(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
dev->conf_ch[channel].conf1.mem_wr_rst = 1;
|
||||
@@ -321,6 +326,7 @@ static inline void rmt_ll_rx_reset_pointer(rmt_dev_t *dev, uint32_t channel)
|
||||
* @param channel RMT RX channel number
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_rx_enable(rmt_dev_t *dev, uint32_t channel, bool enable)
|
||||
{
|
||||
dev->conf_ch[channel].conf1.rx_en = enable;
|
||||
@@ -357,6 +363,7 @@ static inline void rmt_ll_rx_set_idle_thres(rmt_dev_t *dev, uint32_t channel, ui
|
||||
* @param channel RMT RX channel number
|
||||
* @param owner Memory owner
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_rx_set_mem_owner(rmt_dev_t *dev, uint32_t channel, rmt_ll_mem_owner_t owner)
|
||||
{
|
||||
dev->conf_ch[channel].conf1.mem_owner = owner;
|
||||
@@ -393,6 +400,7 @@ static inline void rmt_ll_rx_set_filter_thres(rmt_dev_t *dev, uint32_t channel,
|
||||
* @param channel RMT RX channel number
|
||||
* @return writer offset
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t rmt_ll_rx_get_memory_writer_offset(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
return (dev->status_ch[channel] & 0x3FF) - (channel) * 64;
|
||||
@@ -407,6 +415,7 @@ static inline uint32_t rmt_ll_rx_get_memory_writer_offset(rmt_dev_t *dev, uint32
|
||||
* @param mask Event mask
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_enable_interrupt(rmt_dev_t *dev, uint32_t mask, bool enable)
|
||||
{
|
||||
if (enable) {
|
||||
@@ -422,6 +431,7 @@ static inline void rmt_ll_enable_interrupt(rmt_dev_t *dev, uint32_t mask, bool e
|
||||
* @param dev Peripheral instance address
|
||||
* @param mask Interupt status mask
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_clear_interrupt_status(rmt_dev_t *dev, uint32_t mask)
|
||||
{
|
||||
dev->int_clr.val = mask;
|
||||
@@ -445,6 +455,7 @@ static inline volatile void *rmt_ll_get_interrupt_status_reg(rmt_dev_t *dev)
|
||||
* @param channel RMT TX channel number
|
||||
* @return Interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t rmt_ll_tx_get_interrupt_status(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
return dev->int_st.val & RMT_LL_EVENT_TX_MASK(channel);
|
||||
@@ -469,6 +480,7 @@ static inline uint32_t rmt_ll_tx_get_interrupt_status_raw(rmt_dev_t *dev, uint32
|
||||
* @param channel RMT RX channel number
|
||||
* @return Interrupt raw status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t rmt_ll_rx_get_interrupt_status_raw(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
return dev->int_raw.val & (RMT_LL_EVENT_RX_MASK(channel) | RMT_LL_EVENT_RX_ERROR(channel));
|
||||
@@ -481,6 +493,7 @@ static inline uint32_t rmt_ll_rx_get_interrupt_status_raw(rmt_dev_t *dev, uint32
|
||||
* @param channel RMT RX channel number
|
||||
* @return Interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t rmt_ll_rx_get_interrupt_status(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
return dev->int_st.val & RMT_LL_EVENT_RX_MASK(channel);
|
||||
|
@@ -1,5 +1,5 @@
|
||||
/*
|
||||
* SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
|
||||
* SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
@@ -80,6 +80,7 @@ static inline void timer_ll_set_clock_prescale(timg_dev_t *hw, uint32_t timer_nu
|
||||
* @param en True: enable auto reload mode
|
||||
* False: disable auto reload mode
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void timer_ll_enable_auto_reload(timg_dev_t *hw, uint32_t timer_num, bool en)
|
||||
{
|
||||
hw->hw_timer[timer_num].config.tx_autoreload = en;
|
||||
@@ -151,6 +152,7 @@ static inline void timer_ll_set_alarm_value(timg_dev_t *hw, uint32_t timer_num,
|
||||
* @param timer_num Timer number in the group
|
||||
* @param reload_val Reload counter value
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void timer_ll_set_reload_value(timg_dev_t *hw, uint32_t timer_num, uint64_t load_val)
|
||||
{
|
||||
hw->hw_timer[timer_num].loadhi.tx_load_hi = (uint32_t) (load_val >> 32);
|
||||
|
@@ -303,6 +303,7 @@ static inline void adc_ll_set_power_manage(adc_ll_power_t manage)
|
||||
}
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_set_controller(adc_unit_t adc_n, adc_ll_controller_t ctrl)
|
||||
{
|
||||
//Not used on ESP32-C2
|
||||
@@ -312,6 +313,7 @@ static inline void adc_ll_set_controller(adc_unit_t adc_n, adc_ll_controller_t c
|
||||
/**
|
||||
* @brief Set common calibration configuration. Should be shared with other parts (PWDET).
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_calibration_init(adc_unit_t adc_n)
|
||||
{
|
||||
abort(); //TODO IDF-3908
|
||||
@@ -373,6 +375,7 @@ static inline void adc_ll_calibration_finish(adc_unit_t adc_n)
|
||||
*
|
||||
* @param adc_n ADC index number.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_set_calibration_param(adc_unit_t adc_n, uint32_t param)
|
||||
{
|
||||
abort(); //TODO IDF-3908
|
||||
@@ -554,6 +557,7 @@ static inline void adc_oneshot_ll_set_atten(adc_unit_t adc_n, adc_channel_t chan
|
||||
* @param channel ADCn channel number.
|
||||
* @return atten The attenuation option.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline adc_atten_t adc_ll_get_atten(adc_unit_t adc_n, adc_channel_t channel)
|
||||
{
|
||||
(void)adc_n;
|
||||
|
@@ -18,28 +18,33 @@
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline void dedic_gpio_cpu_ll_enable_output(uint32_t mask)
|
||||
{
|
||||
RV_WRITE_CSR(CSR_GPIO_OEN_USER, mask);
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline void dedic_gpio_cpu_ll_write_all(uint32_t value)
|
||||
{
|
||||
RV_WRITE_CSR(CSR_GPIO_OUT_USER, value);
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t dedic_gpio_cpu_ll_read_in(void)
|
||||
{
|
||||
uint32_t value = RV_READ_CSR(CSR_GPIO_IN_USER);
|
||||
return value;
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t dedic_gpio_cpu_ll_read_out(void)
|
||||
{
|
||||
uint32_t value = RV_READ_CSR(CSR_GPIO_OUT_USER);
|
||||
return value;
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline void dedic_gpio_cpu_ll_write_mask(uint32_t mask, uint32_t value)
|
||||
{
|
||||
RV_SET_CSR(CSR_GPIO_OUT_USER, mask & value);
|
||||
|
@@ -93,6 +93,7 @@ static inline void gpio_ll_set_intr_type(gpio_dev_t *hw, uint32_t gpio_num, gpio
|
||||
* @param core_id interrupt core id
|
||||
* @param status interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_get_intr_status(gpio_dev_t *hw, uint32_t core_id, uint32_t *status)
|
||||
{
|
||||
*status = hw->pcpu_int.procpu_int;
|
||||
@@ -105,6 +106,7 @@ static inline void gpio_ll_get_intr_status(gpio_dev_t *hw, uint32_t core_id, uin
|
||||
* @param core_id interrupt core id
|
||||
* @param status interrupt status high
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
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-C2
|
||||
@@ -116,6 +118,7 @@ static inline void gpio_ll_get_intr_status_high(gpio_dev_t *hw, uint32_t core_id
|
||||
* @param hw Peripheral GPIO hardware instance address.
|
||||
* @param mask interrupt status clear mask
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_clear_intr_status(gpio_dev_t *hw, uint32_t mask)
|
||||
{
|
||||
hw->status_w1tc.status_w1tc = mask;
|
||||
@@ -127,6 +130,7 @@ static inline void gpio_ll_clear_intr_status(gpio_dev_t *hw, uint32_t mask)
|
||||
* @param hw Peripheral GPIO hardware instance address.
|
||||
* @param mask interrupt status high clear mask
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_clear_intr_status_high(gpio_dev_t *hw, uint32_t mask)
|
||||
{
|
||||
// Less than 32 GPIOs in ESP32-C2. Do nothing.
|
||||
@@ -139,6 +143,7 @@ static inline void gpio_ll_clear_intr_status_high(gpio_dev_t *hw, uint32_t mask)
|
||||
* @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);
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_intr_enable_on_core(gpio_dev_t *hw, uint32_t core_id, uint32_t gpio_num)
|
||||
{
|
||||
HAL_ASSERT(core_id == 0 && "target SoC only has a single core");
|
||||
@@ -151,6 +156,7 @@ static inline void gpio_ll_intr_enable_on_core(gpio_dev_t *hw, uint32_t core_id,
|
||||
* @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);
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_intr_disable(gpio_dev_t *hw, uint32_t gpio_num)
|
||||
{
|
||||
hw->pin[gpio_num].int_ena = 0; //disable GPIO intr
|
||||
@@ -232,6 +238,7 @@ static inline void gpio_ll_od_enable(gpio_dev_t *hw, uint32_t gpio_num)
|
||||
* @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
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_set_level(gpio_dev_t *hw, uint32_t gpio_num, uint32_t level)
|
||||
{
|
||||
if (level) {
|
||||
|
@@ -83,6 +83,7 @@ static inline void timer_ll_set_clock_prescale(timg_dev_t *hw, uint32_t timer_nu
|
||||
* @param en True: enable auto reload mode
|
||||
* False: disable auto reload mode
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void timer_ll_enable_auto_reload(timg_dev_t *hw, uint32_t timer_num, bool en)
|
||||
{
|
||||
hw->hw_timer[timer_num].config.tx_autoreload = en;
|
||||
@@ -154,6 +155,7 @@ static inline void timer_ll_set_alarm_value(timg_dev_t *hw, uint32_t timer_num,
|
||||
* @param timer_num Timer number in the group
|
||||
* @param reload_val Reload counter value
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void timer_ll_set_reload_value(timg_dev_t *hw, uint32_t timer_num, uint64_t load_val)
|
||||
{
|
||||
hw->hw_timer[timer_num].loadhi.tx_load_hi = (uint32_t) (load_val >> 32);
|
||||
|
@@ -491,6 +491,7 @@ static inline void adc_ll_set_power_manage(adc_ll_power_t manage)
|
||||
}
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_set_controller(adc_unit_t adc_n, adc_ll_controller_t ctrl)
|
||||
{
|
||||
//Not used on ESP32C3
|
||||
@@ -506,6 +507,7 @@ static inline void adc_ll_set_controller(adc_unit_t adc_n, adc_ll_controller_t c
|
||||
*
|
||||
* @param mode Refer to `adc_arbiter_mode_t`.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_set_arbiter_work_mode(adc_arbiter_mode_t mode)
|
||||
{
|
||||
if (mode == ADC_ARB_MODE_FIX) {
|
||||
@@ -532,6 +534,7 @@ static inline void adc_ll_set_arbiter_work_mode(adc_arbiter_mode_t mode)
|
||||
* @param pri_dig Digital controller priority. Range: 0 ~ 2.
|
||||
* @param pri_pwdet Wi-Fi controller priority. Range: 0 ~ 2.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
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) {
|
||||
@@ -567,6 +570,7 @@ static inline void adc_ll_set_arbiter_priority(uint8_t pri_rtc, uint8_t pri_dig,
|
||||
/**
|
||||
* @brief Set common calibration configuration. Should be shared with other parts (PWDET).
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_calibration_init(adc_unit_t adc_n)
|
||||
{
|
||||
if (adc_n == ADC_UNIT_1) {
|
||||
@@ -624,6 +628,7 @@ static inline void adc_ll_calibration_finish(adc_unit_t adc_n)
|
||||
*
|
||||
* @param adc_n ADC index number.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_set_calibration_param(adc_unit_t adc_n, uint32_t param)
|
||||
{
|
||||
uint8_t msb = param >> 8;
|
||||
@@ -875,6 +880,7 @@ static inline void adc_oneshot_ll_set_atten(adc_unit_t adc_n, adc_channel_t chan
|
||||
* @param channel ADCn channel number.
|
||||
* @return atten The attenuation option.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline adc_atten_t adc_ll_get_atten(adc_unit_t adc_n, adc_channel_t channel)
|
||||
{
|
||||
(void)adc_n;
|
||||
|
@@ -18,6 +18,7 @@
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline void dedic_gpio_cpu_ll_enable_output(uint32_t mask)
|
||||
{
|
||||
RV_WRITE_CSR(CSR_GPIO_OEN_USER, mask);
|
||||
@@ -28,18 +29,21 @@ static inline void dedic_gpio_cpu_ll_write_all(uint32_t value)
|
||||
RV_WRITE_CSR(CSR_GPIO_OUT_USER, value);
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t dedic_gpio_cpu_ll_read_in(void)
|
||||
{
|
||||
uint32_t value = RV_READ_CSR(CSR_GPIO_IN_USER);
|
||||
return value;
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t dedic_gpio_cpu_ll_read_out(void)
|
||||
{
|
||||
uint32_t value = RV_READ_CSR(CSR_GPIO_OUT_USER);
|
||||
return value;
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline void dedic_gpio_cpu_ll_write_mask(uint32_t mask, uint32_t value)
|
||||
{
|
||||
RV_SET_CSR(CSR_GPIO_OUT_USER, mask & value);
|
||||
|
@@ -95,6 +95,7 @@ static inline void gpio_ll_set_intr_type(gpio_dev_t *hw, uint32_t gpio_num, gpio
|
||||
* @param core_id interrupt core id
|
||||
* @param status interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_get_intr_status(gpio_dev_t *hw, uint32_t core_id, uint32_t *status)
|
||||
{
|
||||
*status = hw->pcpu_int.intr;
|
||||
@@ -107,6 +108,7 @@ static inline void gpio_ll_get_intr_status(gpio_dev_t *hw, uint32_t core_id, uin
|
||||
* @param core_id interrupt core id
|
||||
* @param status interrupt status high
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
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
|
||||
@@ -118,6 +120,7 @@ static inline void gpio_ll_get_intr_status_high(gpio_dev_t *hw, uint32_t core_id
|
||||
* @param hw Peripheral GPIO hardware instance address.
|
||||
* @param mask interrupt status clear mask
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_clear_intr_status(gpio_dev_t *hw, uint32_t mask)
|
||||
{
|
||||
hw->status_w1tc.status_w1tc = mask;
|
||||
@@ -129,6 +132,7 @@ static inline void gpio_ll_clear_intr_status(gpio_dev_t *hw, uint32_t mask)
|
||||
* @param hw Peripheral GPIO hardware instance address.
|
||||
* @param mask interrupt status high clear mask
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_clear_intr_status_high(gpio_dev_t *hw, uint32_t mask)
|
||||
{
|
||||
// Less than 32 GPIOs on ESP32-C3. Do nothing.
|
||||
@@ -141,6 +145,7 @@ static inline void gpio_ll_clear_intr_status_high(gpio_dev_t *hw, uint32_t mask)
|
||||
* @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);
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_intr_enable_on_core(gpio_dev_t *hw, uint32_t core_id, uint32_t gpio_num)
|
||||
{
|
||||
HAL_ASSERT(core_id == 0 && "target SoC only has a single core");
|
||||
@@ -153,6 +158,7 @@ static inline void gpio_ll_intr_enable_on_core(gpio_dev_t *hw, uint32_t core_id,
|
||||
* @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);
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_intr_disable(gpio_dev_t *hw, uint32_t gpio_num)
|
||||
{
|
||||
hw->pin[gpio_num].int_ena = 0; //disable GPIO intr
|
||||
@@ -234,6 +240,7 @@ static inline void gpio_ll_od_enable(gpio_dev_t *hw, uint32_t gpio_num)
|
||||
* @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
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_set_level(gpio_dev_t *hw, uint32_t gpio_num, uint32_t level)
|
||||
{
|
||||
if (level) {
|
||||
|
@@ -148,6 +148,7 @@ static inline void rmt_ll_tx_set_channel_clock_div(rmt_dev_t *dev, uint32_t chan
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT TX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_reset_pointer(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
dev->tx_conf[channel].mem_rd_rst = 1;
|
||||
@@ -162,6 +163,7 @@ static inline void rmt_ll_tx_reset_pointer(rmt_dev_t *dev, uint32_t channel)
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT TX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_start(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
// update other configuration registers before start transmitting
|
||||
@@ -175,6 +177,7 @@ static inline void rmt_ll_tx_start(rmt_dev_t *dev, uint32_t channel)
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT TX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_stop(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
dev->tx_conf[channel].tx_stop = 1;
|
||||
@@ -213,6 +216,7 @@ static inline void rmt_ll_tx_enable_wrap(rmt_dev_t *dev, uint32_t channel, bool
|
||||
* @param channel RMT TX channel number
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
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;
|
||||
@@ -225,6 +229,7 @@ static inline void rmt_ll_tx_enable_loop(rmt_dev_t *dev, uint32_t channel, bool
|
||||
* @param channel RMT TX channel number
|
||||
* @param count TX loop count
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_set_loop_count(rmt_dev_t *dev, uint32_t channel, uint32_t count)
|
||||
{
|
||||
HAL_ASSERT(count <= RMT_LL_MAX_LOOP_COUNT_PER_BATCH && "loop count out of range");
|
||||
@@ -237,6 +242,7 @@ static inline void rmt_ll_tx_set_loop_count(rmt_dev_t *dev, uint32_t channel, ui
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT TX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_reset_loop_count(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
dev->tx_lim[channel].loop_count_reset = 1;
|
||||
@@ -250,6 +256,7 @@ static inline void rmt_ll_tx_reset_loop_count(rmt_dev_t *dev, uint32_t channel)
|
||||
* @param channel RMT TX channel number
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
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;
|
||||
@@ -306,6 +313,7 @@ static inline void rmt_ll_tx_sync_group_remove_channels(rmt_dev_t *dev, uint32_t
|
||||
* @param level IDLE level (1 => high, 0 => low)
|
||||
* @param enable True to fix the IDLE level, otherwise the IDLE level is determined by EOF encoder
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_fix_idle_level(rmt_dev_t *dev, uint32_t channel, uint8_t level, bool enable)
|
||||
{
|
||||
dev->tx_conf[channel].idle_out_en = enable;
|
||||
@@ -434,6 +442,7 @@ static inline void rmt_ll_rx_reset_pointer(rmt_dev_t *dev, uint32_t channel)
|
||||
* @param channel RMT RX channel number
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_rx_enable(rmt_dev_t *dev, uint32_t channel, bool enable)
|
||||
{
|
||||
dev->rx_conf[channel].conf1.rx_en = enable;
|
||||
@@ -472,6 +481,7 @@ static inline void rmt_ll_rx_set_idle_thres(rmt_dev_t *dev, uint32_t channel, ui
|
||||
* @param channel RMT RX channel number
|
||||
* @param owner Memory owner
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_rx_set_mem_owner(rmt_dev_t *dev, uint32_t channel, rmt_ll_mem_owner_t owner)
|
||||
{
|
||||
dev->rx_conf[channel].conf1.mem_owner = owner;
|
||||
@@ -508,6 +518,7 @@ static inline void rmt_ll_rx_set_filter_thres(rmt_dev_t *dev, uint32_t channel,
|
||||
* @param channel RMT RX channel number
|
||||
* @return writer offset
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t rmt_ll_rx_get_memory_writer_offset(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
return dev->rx_status[channel].mem_waddr_ex - (channel + 2) * 48;
|
||||
@@ -585,6 +596,7 @@ static inline void rmt_ll_rx_enable_wrap(rmt_dev_t *dev, uint32_t channel, bool
|
||||
* @param mask Event mask
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_enable_interrupt(rmt_dev_t *dev, uint32_t mask, bool enable)
|
||||
{
|
||||
if (enable) {
|
||||
@@ -600,6 +612,7 @@ static inline void rmt_ll_enable_interrupt(rmt_dev_t *dev, uint32_t mask, bool e
|
||||
* @param dev Peripheral instance address
|
||||
* @param mask Interupt status mask
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_clear_interrupt_status(rmt_dev_t *dev, uint32_t mask)
|
||||
{
|
||||
dev->int_clr.val = mask;
|
||||
@@ -623,6 +636,7 @@ static inline volatile void *rmt_ll_get_interrupt_status_reg(rmt_dev_t *dev)
|
||||
* @param channel RMT TX channel number
|
||||
* @return Interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t rmt_ll_tx_get_interrupt_status(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
return dev->int_st.val & RMT_LL_EVENT_TX_MASK(channel);
|
||||
@@ -659,6 +673,7 @@ static inline uint32_t rmt_ll_rx_get_interrupt_status_raw(rmt_dev_t *dev, uint32
|
||||
* @param channel RMT RX channel number
|
||||
* @return Interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t rmt_ll_rx_get_interrupt_status(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
return dev->int_st.val & RMT_LL_EVENT_RX_MASK(channel);
|
||||
|
@@ -1,5 +1,5 @@
|
||||
/*
|
||||
* SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
|
||||
* SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
@@ -83,6 +83,7 @@ static inline void timer_ll_set_clock_prescale(timg_dev_t *hw, uint32_t timer_nu
|
||||
* @param en True: enable auto reload mode
|
||||
* False: disable auto reload mode
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void timer_ll_enable_auto_reload(timg_dev_t *hw, uint32_t timer_num, bool en)
|
||||
{
|
||||
hw->hw_timer[timer_num].config.tx_autoreload = en;
|
||||
@@ -154,6 +155,7 @@ static inline void timer_ll_set_alarm_value(timg_dev_t *hw, uint32_t timer_num,
|
||||
* @param timer_num Timer number in the group
|
||||
* @param reload_val Reload counter value
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void timer_ll_set_reload_value(timg_dev_t *hw, uint32_t timer_num, uint64_t load_val)
|
||||
{
|
||||
hw->hw_timer[timer_num].loadhi.tx_load_hi = (uint32_t) (load_val >> 32);
|
||||
|
@@ -521,6 +521,7 @@ static inline void adc_ll_set_power_manage(adc_ll_power_t manage)
|
||||
}
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_set_controller(adc_unit_t adc_n, adc_ll_controller_t ctrl)
|
||||
{
|
||||
//Not used on ESP32H2
|
||||
@@ -536,6 +537,7 @@ static inline void adc_ll_set_controller(adc_unit_t adc_n, adc_ll_controller_t c
|
||||
*
|
||||
* @param mode Refer to `adc_arbiter_mode_t`.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_set_arbiter_work_mode(adc_arbiter_mode_t mode)
|
||||
{
|
||||
if (mode == ADC_ARB_MODE_FIX) {
|
||||
@@ -562,6 +564,7 @@ static inline void adc_ll_set_arbiter_work_mode(adc_arbiter_mode_t mode)
|
||||
* @param pri_dig Digital controller priority. Range: 0 ~ 2.
|
||||
* @param pri_pwdet Wi-Fi controller priority. Range: 0 ~ 2.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
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) {
|
||||
@@ -597,6 +600,7 @@ static inline void adc_ll_set_arbiter_priority(uint8_t pri_rtc, uint8_t pri_dig,
|
||||
/**
|
||||
* @brief Set common calibration configuration. Should be shared with other parts (PWDET).
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_calibration_init(adc_unit_t adc_n)
|
||||
{
|
||||
if (adc_n == ADC_UNIT_1) {
|
||||
@@ -655,6 +659,7 @@ static inline void adc_ll_calibration_finish(adc_unit_t adc_n)
|
||||
*
|
||||
* @param adc_n ADC index number.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_set_calibration_param(adc_unit_t adc_n, uint32_t param)
|
||||
{
|
||||
uint8_t msb = param >> 8;
|
||||
|
@@ -18,28 +18,33 @@
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline void dedic_gpio_cpu_ll_enable_output(uint32_t mask)
|
||||
{
|
||||
RV_WRITE_CSR(CSR_GPIO_OEN_USER, mask);
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline void dedic_gpio_cpu_ll_write_all(uint32_t value)
|
||||
{
|
||||
RV_WRITE_CSR(CSR_GPIO_OUT_USER, value);
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t dedic_gpio_cpu_ll_read_in(void)
|
||||
{
|
||||
uint32_t value = RV_READ_CSR(CSR_GPIO_IN_USER);
|
||||
return value;
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t dedic_gpio_cpu_ll_read_out(void)
|
||||
{
|
||||
uint32_t value = RV_READ_CSR(CSR_GPIO_OUT_USER);
|
||||
return value;
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline void dedic_gpio_cpu_ll_write_mask(uint32_t mask, uint32_t value)
|
||||
{
|
||||
RV_SET_CSR(CSR_GPIO_OUT_USER, mask & value);
|
||||
|
@@ -148,6 +148,7 @@ static inline void rmt_ll_tx_set_channel_clock_div(rmt_dev_t *dev, uint32_t chan
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT TX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_reset_pointer(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
dev->tx_conf[channel].mem_rd_rst = 1;
|
||||
@@ -162,6 +163,7 @@ static inline void rmt_ll_tx_reset_pointer(rmt_dev_t *dev, uint32_t channel)
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT TX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_start(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
// update other configuration registers before start transmitting
|
||||
@@ -175,6 +177,7 @@ static inline void rmt_ll_tx_start(rmt_dev_t *dev, uint32_t channel)
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT TX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_stop(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
dev->tx_conf[channel].tx_stop = 1;
|
||||
@@ -213,6 +216,7 @@ static inline void rmt_ll_tx_enable_wrap(rmt_dev_t *dev, uint32_t channel, bool
|
||||
* @param channel RMT TX channel number
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
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;
|
||||
@@ -225,6 +229,7 @@ static inline void rmt_ll_tx_enable_loop(rmt_dev_t *dev, uint32_t channel, bool
|
||||
* @param channel RMT TX channel number
|
||||
* @param count TX loop count
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_set_loop_count(rmt_dev_t *dev, uint32_t channel, uint32_t count)
|
||||
{
|
||||
HAL_ASSERT(count <= RMT_LL_MAX_LOOP_COUNT_PER_BATCH && "loop count out of range");
|
||||
@@ -237,6 +242,7 @@ static inline void rmt_ll_tx_set_loop_count(rmt_dev_t *dev, uint32_t channel, ui
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT TX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_reset_loop_count(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
dev->tx_lim[channel].loop_count_reset = 1;
|
||||
@@ -250,6 +256,7 @@ static inline void rmt_ll_tx_reset_loop_count(rmt_dev_t *dev, uint32_t channel)
|
||||
* @param channel RMT TX channel number
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
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;
|
||||
@@ -306,6 +313,7 @@ static inline void rmt_ll_tx_sync_group_remove_channels(rmt_dev_t *dev, uint32_t
|
||||
* @param level IDLE level (1 => high, 0 => low)
|
||||
* @param enable True to fix the IDLE level, otherwise the IDLE level is determined by EOF encoder
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_fix_idle_level(rmt_dev_t *dev, uint32_t channel, uint8_t level, bool enable)
|
||||
{
|
||||
dev->tx_conf[channel].idle_out_en = enable;
|
||||
@@ -434,6 +442,7 @@ static inline void rmt_ll_rx_reset_pointer(rmt_dev_t *dev, uint32_t channel)
|
||||
* @param channel RMT RX channel number
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_rx_enable(rmt_dev_t *dev, uint32_t channel, bool enable)
|
||||
{
|
||||
dev->rx_conf[channel].conf1.rx_en = enable;
|
||||
@@ -472,6 +481,7 @@ static inline void rmt_ll_rx_set_idle_thres(rmt_dev_t *dev, uint32_t channel, ui
|
||||
* @param channel RMT RX channel number
|
||||
* @param owner Memory owner
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_rx_set_mem_owner(rmt_dev_t *dev, uint32_t channel, rmt_ll_mem_owner_t owner)
|
||||
{
|
||||
dev->rx_conf[channel].conf1.mem_owner = owner;
|
||||
@@ -508,6 +518,7 @@ static inline void rmt_ll_rx_set_filter_thres(rmt_dev_t *dev, uint32_t channel,
|
||||
* @param channel RMT RX channel number
|
||||
* @return writer offset
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t rmt_ll_rx_get_memory_writer_offset(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
return dev->rx_status[channel].mem_waddr_ex - (channel + 2) * 48;
|
||||
@@ -585,6 +596,7 @@ static inline void rmt_ll_rx_enable_wrap(rmt_dev_t *dev, uint32_t channel, bool
|
||||
* @param mask Event mask
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_enable_interrupt(rmt_dev_t *dev, uint32_t mask, bool enable)
|
||||
{
|
||||
if (enable) {
|
||||
@@ -600,6 +612,7 @@ static inline void rmt_ll_enable_interrupt(rmt_dev_t *dev, uint32_t mask, bool e
|
||||
* @param dev Peripheral instance address
|
||||
* @param mask Interupt status mask
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_clear_interrupt_status(rmt_dev_t *dev, uint32_t mask)
|
||||
{
|
||||
dev->int_clr.val = mask;
|
||||
@@ -623,6 +636,7 @@ static inline volatile void *rmt_ll_get_interrupt_status_reg(rmt_dev_t *dev)
|
||||
* @param channel RMT TX channel number
|
||||
* @return Interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t rmt_ll_tx_get_interrupt_status(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
return dev->int_st.val & RMT_LL_EVENT_TX_MASK(channel);
|
||||
@@ -659,6 +673,7 @@ static inline uint32_t rmt_ll_rx_get_interrupt_status_raw(rmt_dev_t *dev, uint32
|
||||
* @param channel RMT RX channel number
|
||||
* @return Interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t rmt_ll_rx_get_interrupt_status(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
return dev->int_st.val & RMT_LL_EVENT_RX_MASK(channel);
|
||||
|
@@ -83,6 +83,7 @@ static inline void timer_ll_set_clock_prescale(timg_dev_t *hw, uint32_t timer_nu
|
||||
* @param en True: enable auto reload mode
|
||||
* False: disable auto reload mode
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void timer_ll_enable_auto_reload(timg_dev_t *hw, uint32_t timer_num, bool en)
|
||||
{
|
||||
hw->hw_timer[timer_num].config.tx_autoreload = en;
|
||||
@@ -154,6 +155,7 @@ static inline void timer_ll_set_alarm_value(timg_dev_t *hw, uint32_t timer_num,
|
||||
* @param timer_num Timer number in the group
|
||||
* @param reload_val Reload counter value
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void timer_ll_set_reload_value(timg_dev_t *hw, uint32_t timer_num, uint64_t load_val)
|
||||
{
|
||||
hw->hw_timer[timer_num].loadhi.tx_load_hi = (uint32_t) (load_val >> 32);
|
||||
|
@@ -95,6 +95,7 @@ static inline void gpio_ll_set_intr_type(gpio_dev_t *hw, uint32_t gpio_num, gpio
|
||||
* @param core_id interrupt core id
|
||||
* @param status interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_get_intr_status(gpio_dev_t *hw, uint32_t core_id, uint32_t *status)
|
||||
{
|
||||
*status = hw->pcpu_int.procpu_int;
|
||||
@@ -107,6 +108,7 @@ static inline void gpio_ll_get_intr_status(gpio_dev_t *hw, uint32_t core_id, uin
|
||||
* @param core_id interrupt core id
|
||||
* @param status interrupt status high
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_get_intr_status_high(gpio_dev_t *hw, uint32_t core_id, uint32_t *status)
|
||||
{
|
||||
*status = hw->pcpu_int1.procpu_int1;
|
||||
@@ -118,6 +120,7 @@ static inline void gpio_ll_get_intr_status_high(gpio_dev_t *hw, uint32_t core_id
|
||||
* @param hw Peripheral GPIO hardware instance address.
|
||||
* @param mask interrupt status clear mask
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_clear_intr_status(gpio_dev_t *hw, uint32_t mask)
|
||||
{
|
||||
hw->status_w1tc.status_w1tc = mask;
|
||||
@@ -129,6 +132,7 @@ static inline void gpio_ll_clear_intr_status(gpio_dev_t *hw, uint32_t mask)
|
||||
* @param hw Peripheral GPIO hardware instance address.
|
||||
* @param mask interrupt status high clear mask
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_clear_intr_status_high(gpio_dev_t *hw, uint32_t mask)
|
||||
{
|
||||
hw->status1_w1tc.status1_w1tc = mask;
|
||||
@@ -141,6 +145,7 @@ static inline void gpio_ll_clear_intr_status_high(gpio_dev_t *hw, uint32_t mask)
|
||||
* @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);
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_intr_enable_on_core(gpio_dev_t *hw, uint32_t core_id, uint32_t gpio_num)
|
||||
{
|
||||
HAL_ASSERT(core_id == 0 && "target SoC only has a single core");
|
||||
@@ -153,6 +158,7 @@ static inline void gpio_ll_intr_enable_on_core(gpio_dev_t *hw, uint32_t core_id,
|
||||
* @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);
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_intr_disable(gpio_dev_t *hw, uint32_t gpio_num)
|
||||
{
|
||||
hw->pin[gpio_num].pin_int_ena = 0; //disable GPIO intr
|
||||
@@ -242,6 +248,7 @@ static inline void gpio_ll_od_enable(gpio_dev_t *hw, uint32_t gpio_num)
|
||||
* @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
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_set_level(gpio_dev_t *hw, uint32_t gpio_num, uint32_t level)
|
||||
{
|
||||
if (level) {
|
||||
|
@@ -95,6 +95,7 @@ static inline void gpio_ll_set_intr_type(gpio_dev_t *hw, uint32_t gpio_num, gpio
|
||||
* @param core_id interrupt core id
|
||||
* @param status interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_get_intr_status(gpio_dev_t *hw, uint32_t core_id, uint32_t *status)
|
||||
{
|
||||
*status = hw->pcpu_int.procpu_int;
|
||||
@@ -107,6 +108,7 @@ static inline void gpio_ll_get_intr_status(gpio_dev_t *hw, uint32_t core_id, uin
|
||||
* @param core_id interrupt core id
|
||||
* @param status interrupt status high
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
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-H2Beta2
|
||||
@@ -118,6 +120,7 @@ static inline void gpio_ll_get_intr_status_high(gpio_dev_t *hw, uint32_t core_id
|
||||
* @param hw Peripheral GPIO hardware instance address.
|
||||
* @param mask interrupt status clear mask
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_clear_intr_status(gpio_dev_t *hw, uint32_t mask)
|
||||
{
|
||||
hw->status_w1tc.status_w1tc = mask;
|
||||
@@ -129,6 +132,7 @@ static inline void gpio_ll_clear_intr_status(gpio_dev_t *hw, uint32_t mask)
|
||||
* @param hw Peripheral GPIO hardware instance address.
|
||||
* @param mask interrupt status high clear mask
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_clear_intr_status_high(gpio_dev_t *hw, uint32_t mask)
|
||||
{
|
||||
// Less than 32 GPIOs in ESP32-H2Beta2. Do nothing.
|
||||
@@ -141,6 +145,7 @@ static inline void gpio_ll_clear_intr_status_high(gpio_dev_t *hw, uint32_t mask)
|
||||
* @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);
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_intr_enable_on_core(gpio_dev_t *hw, uint32_t core_id, uint32_t gpio_num)
|
||||
{
|
||||
HAL_ASSERT(core_id == 0 && "target SoC only has a single core");
|
||||
@@ -153,6 +158,7 @@ static inline void gpio_ll_intr_enable_on_core(gpio_dev_t *hw, uint32_t core_id,
|
||||
* @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);
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_intr_disable(gpio_dev_t *hw, uint32_t gpio_num)
|
||||
{
|
||||
hw->pin[gpio_num].pin_int_ena = 0; //disable GPIO intr
|
||||
@@ -234,6 +240,7 @@ static inline void gpio_ll_od_enable(gpio_dev_t *hw, uint32_t gpio_num)
|
||||
* @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
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_set_level(gpio_dev_t *hw, uint32_t gpio_num, uint32_t level)
|
||||
{
|
||||
if (level) {
|
||||
|
@@ -837,6 +837,7 @@ static inline void adc_oneshot_ll_set_atten(adc_unit_t adc_n, adc_channel_t chan
|
||||
* @param channel ADCn channel number.
|
||||
* @return atten The attenuation option.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline adc_atten_t adc_ll_get_atten(adc_unit_t adc_n, adc_channel_t channel)
|
||||
{
|
||||
if (adc_n == ADC_UNIT_1) {
|
||||
@@ -899,6 +900,7 @@ static inline void adc_ll_set_power_manage(adc_ll_power_t manage)
|
||||
* @param adc_n ADC unit.
|
||||
* @param ctrl ADC controller.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_set_controller(adc_unit_t adc_n, adc_ll_controller_t ctrl)
|
||||
{
|
||||
if (adc_n == ADC_UNIT_1) {
|
||||
@@ -948,6 +950,7 @@ static inline void adc_ll_set_controller(adc_unit_t adc_n, adc_ll_controller_t c
|
||||
*
|
||||
* @param mode Refer to ``adc_arbiter_mode_t``.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_set_arbiter_work_mode(adc_arbiter_mode_t mode)
|
||||
{
|
||||
SENS.sar_meas2_mux.sar2_rtc_force = 0; // Enable arbiter in wakeup mode
|
||||
@@ -975,6 +978,7 @@ static inline void adc_ll_set_arbiter_work_mode(adc_arbiter_mode_t mode)
|
||||
* @param pri_dig Digital controller priority. Range: 0 ~ 2.
|
||||
* @param pri_pwdet Wi-Fi controller priority. Range: 0 ~ 2.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
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) {
|
||||
@@ -1038,6 +1042,7 @@ static inline void adc_ll_disable_sleep_controller(void)
|
||||
/**
|
||||
* @brief Set common calibration configuration. Should be shared with other parts (PWDET).
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_calibration_init(adc_unit_t adc_n)
|
||||
{
|
||||
if (adc_n == ADC_UNIT_1) {
|
||||
@@ -1101,6 +1106,7 @@ static inline void adc_ll_calibration_finish(adc_unit_t adc_n)
|
||||
*
|
||||
* @param adc_n ADC index number.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_set_calibration_param(adc_unit_t adc_n, uint32_t param)
|
||||
{
|
||||
uint8_t msb = param >> 8;
|
||||
|
@@ -12,6 +12,7 @@
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t dedic_gpio_cpu_ll_read_in(void)
|
||||
{
|
||||
uint32_t value = 0;
|
||||
@@ -19,6 +20,7 @@ static inline uint32_t dedic_gpio_cpu_ll_read_in(void)
|
||||
return value;
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t dedic_gpio_cpu_ll_read_out(void)
|
||||
{
|
||||
uint32_t value = 0;
|
||||
@@ -26,11 +28,13 @@ static inline uint32_t dedic_gpio_cpu_ll_read_out(void)
|
||||
return value;
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline void dedic_gpio_cpu_ll_write_all(uint32_t value)
|
||||
{
|
||||
asm volatile("wur.gpio_out %0"::"r"(value):);
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline void dedic_gpio_cpu_ll_write_mask(uint32_t mask, uint32_t value)
|
||||
{
|
||||
asm volatile("wr_mask_gpio_out %0, %1" : : "r"(value), "r"(mask):);
|
||||
|
@@ -95,6 +95,7 @@ static inline void gpio_ll_set_intr_type(gpio_dev_t *hw, uint32_t gpio_num, gpio
|
||||
* @param core_id interrupt core id
|
||||
* @param status interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_get_intr_status(gpio_dev_t *hw, uint32_t core_id, uint32_t *status)
|
||||
{
|
||||
*status = hw->pcpu_int;
|
||||
@@ -107,6 +108,7 @@ static inline void gpio_ll_get_intr_status(gpio_dev_t *hw, uint32_t core_id, uin
|
||||
* @param core_id interrupt core id
|
||||
* @param status interrupt status high
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_get_intr_status_high(gpio_dev_t *hw, uint32_t core_id, uint32_t *status)
|
||||
{
|
||||
*status = hw->pcpu_int1.intr;
|
||||
@@ -118,6 +120,7 @@ static inline void gpio_ll_get_intr_status_high(gpio_dev_t *hw, uint32_t core_id
|
||||
* @param hw Peripheral GPIO hardware instance address.
|
||||
* @param mask interrupt status clear mask
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_clear_intr_status(gpio_dev_t *hw, uint32_t mask)
|
||||
{
|
||||
hw->status_w1tc = mask;
|
||||
@@ -129,6 +132,7 @@ static inline void gpio_ll_clear_intr_status(gpio_dev_t *hw, uint32_t mask)
|
||||
* @param hw Peripheral GPIO hardware instance address.
|
||||
* @param mask interrupt status high clear mask
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_clear_intr_status_high(gpio_dev_t *hw, uint32_t mask)
|
||||
{
|
||||
hw->status1_w1tc.intr_st = mask;
|
||||
@@ -141,6 +145,7 @@ static inline void gpio_ll_clear_intr_status_high(gpio_dev_t *hw, uint32_t mask)
|
||||
* @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);
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_intr_enable_on_core(gpio_dev_t *hw, uint32_t core_id, uint32_t gpio_num)
|
||||
{
|
||||
HAL_ASSERT(core_id == 0 && "target SoC only has a single core");
|
||||
@@ -153,6 +158,7 @@ static inline void gpio_ll_intr_enable_on_core(gpio_dev_t *hw, uint32_t core_id,
|
||||
* @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);
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_intr_disable(gpio_dev_t *hw, uint32_t gpio_num)
|
||||
{
|
||||
hw->pin[gpio_num].int_ena = 0; //disable GPIO intr
|
||||
@@ -243,6 +249,7 @@ static inline void gpio_ll_od_enable(gpio_dev_t *hw, uint32_t gpio_num)
|
||||
* @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
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_set_level(gpio_dev_t *hw, uint32_t gpio_num, uint32_t level)
|
||||
{
|
||||
if (level) {
|
||||
|
@@ -439,6 +439,7 @@ static inline volatile void *i2s_ll_get_intr_status_reg(i2s_dev_t *hw)
|
||||
* @return
|
||||
* - module interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t i2s_ll_get_intr_status(i2s_dev_t *hw)
|
||||
{
|
||||
return hw->int_st.val;
|
||||
@@ -458,6 +459,7 @@ static inline volatile void *i2s_ll_get_interrupt_status_reg(i2s_dev_t *hw)
|
||||
* @param hw Peripheral I2S hardware instance address.
|
||||
* @param clr_mask Interrupt mask to be cleared.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void i2s_ll_clear_intr_status(i2s_dev_t *hw, uint32_t clr_mask)
|
||||
{
|
||||
hw->int_clr.val = clr_mask;
|
||||
@@ -640,6 +642,7 @@ static inline void i2s_ll_rx_stop_link(i2s_dev_t *hw)
|
||||
* @param hw Peripheral I2S hardware instance address.
|
||||
* @param eof_addr Pointer to accept out eof des address
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void i2s_ll_tx_get_eof_des_addr(i2s_dev_t *hw, uint32_t *eof_addr)
|
||||
{
|
||||
*eof_addr = hw->out_eof_des_addr;
|
||||
@@ -651,6 +654,7 @@ static inline void i2s_ll_tx_get_eof_des_addr(i2s_dev_t *hw, uint32_t *eof_addr)
|
||||
* @param hw Peripheral I2S hardware instance address.
|
||||
* @param eof_addr Pointer to accept in eof des address
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void i2s_ll_rx_get_eof_des_addr(i2s_dev_t *hw, uint32_t *eof_addr)
|
||||
{
|
||||
*eof_addr = hw->in_eof_des_addr;
|
||||
|
@@ -89,6 +89,7 @@ static inline void pcnt_ll_set_level_action(pcnt_dev_t *hw, uint32_t unit, uint3
|
||||
* @param unit Pulse Counter unit number
|
||||
* @return PCNT count value (a signed integer)
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline int pcnt_ll_get_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
{
|
||||
pcnt_un_cnt_reg_t cnt_reg = hw->cnt_unit[unit];
|
||||
@@ -102,6 +103,7 @@ static inline int pcnt_ll_get_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
* @param hw Peripheral PCNT hardware instance address.
|
||||
* @param unit PCNT unit number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void pcnt_ll_stop_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
{
|
||||
hw->ctrl.val |= 1 << (2 * unit + 1);
|
||||
@@ -113,6 +115,7 @@ static inline void pcnt_ll_stop_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
* @param hw Peripheral PCNT hardware instance address.
|
||||
* @param unit PCNT unit number, select from uint32_t
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void pcnt_ll_start_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
{
|
||||
hw->ctrl.val &= ~(1 << (2 * unit + 1));
|
||||
@@ -124,6 +127,7 @@ static inline void pcnt_ll_start_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
* @param hw Peripheral PCNT hardware instance address.
|
||||
* @param unit PCNT unit number, select from uint32_t
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void pcnt_ll_clear_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
{
|
||||
hw->ctrl.val |= 1 << (2 * unit);
|
||||
|
@@ -141,6 +141,7 @@ static inline void rmt_ll_tx_set_channel_clock_div(rmt_dev_t *dev, uint32_t chan
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT TX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_reset_pointer(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
dev->conf_ch[channel].conf1.mem_rd_rst_chn = 1;
|
||||
@@ -155,6 +156,7 @@ static inline void rmt_ll_tx_reset_pointer(rmt_dev_t *dev, uint32_t channel)
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT TX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_start(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
dev->conf_ch[channel].conf1.tx_start_chn = 1;
|
||||
@@ -166,6 +168,7 @@ static inline void rmt_ll_tx_start(rmt_dev_t *dev, uint32_t channel)
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT TX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_stop(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
dev->conf_ch[channel].conf1.tx_stop_chn = 1;
|
||||
@@ -202,6 +205,7 @@ static inline void rmt_ll_tx_enable_wrap(rmt_dev_t *dev, uint32_t channel, bool
|
||||
* @param channel RMT TX channel number
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_enable_loop(rmt_dev_t *dev, uint32_t channel, bool enable)
|
||||
{
|
||||
dev->conf_ch[channel].conf1.tx_conti_mode_chn = enable;
|
||||
@@ -214,6 +218,7 @@ static inline void rmt_ll_tx_enable_loop(rmt_dev_t *dev, uint32_t channel, bool
|
||||
* @param channel RMT TX channel number
|
||||
* @param count TX loop count
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_set_loop_count(rmt_dev_t *dev, uint32_t channel, uint32_t count)
|
||||
{
|
||||
HAL_ASSERT(count <= RMT_LL_MAX_LOOP_COUNT_PER_BATCH && "loop count out of range");
|
||||
@@ -226,6 +231,7 @@ static inline void rmt_ll_tx_set_loop_count(rmt_dev_t *dev, uint32_t channel, ui
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT TX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_reset_loop_count(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
dev->chn_tx_lim[channel].loop_count_reset_chn = 1;
|
||||
@@ -239,6 +245,7 @@ static inline void rmt_ll_tx_reset_loop_count(rmt_dev_t *dev, uint32_t channel)
|
||||
* @param channel RMT TX channel number
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_enable_loop_count(rmt_dev_t *dev, uint32_t channel, bool enable)
|
||||
{
|
||||
dev->chn_tx_lim[channel].tx_loop_cnt_en_chn = enable;
|
||||
@@ -295,6 +302,7 @@ static inline void rmt_ll_tx_sync_group_remove_channels(rmt_dev_t *dev, uint32_t
|
||||
* @param level IDLE level (1 => high, 0 => low)
|
||||
* @param enable True to fix the IDLE level, otherwise the IDLE level is determined by EOF encoder
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_fix_idle_level(rmt_dev_t *dev, uint32_t channel, uint8_t level, bool enable)
|
||||
{
|
||||
dev->conf_ch[channel].conf1.idle_out_en_chn = enable;
|
||||
@@ -408,6 +416,7 @@ static inline void rmt_ll_rx_set_channel_clock_div(rmt_dev_t *dev, uint32_t chan
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT RX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_rx_reset_pointer(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
dev->conf_ch[channel].conf1.mem_wr_rst_chn = 1;
|
||||
@@ -423,6 +432,7 @@ static inline void rmt_ll_rx_reset_pointer(rmt_dev_t *dev, uint32_t channel)
|
||||
* @param channel RMT RX channel number
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_rx_enable(rmt_dev_t *dev, uint32_t channel, bool enable)
|
||||
{
|
||||
dev->conf_ch[channel].conf1.rx_en_chn = enable;
|
||||
@@ -459,6 +469,7 @@ static inline void rmt_ll_rx_set_idle_thres(rmt_dev_t *dev, uint32_t channel, ui
|
||||
* @param channel RMT RX channel number
|
||||
* @param owner Memory owner
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_rx_set_mem_owner(rmt_dev_t *dev, uint32_t channel, rmt_ll_mem_owner_t owner)
|
||||
{
|
||||
dev->conf_ch[channel].conf1.mem_owner_chn = owner;
|
||||
@@ -495,6 +506,7 @@ static inline void rmt_ll_rx_set_filter_thres(rmt_dev_t *dev, uint32_t channel,
|
||||
* @param channel RMT RX channel number
|
||||
* @return writer offset
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t rmt_ll_rx_get_memory_writer_offset(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
return dev->chnstatus[channel].mem_waddr_ex_chn - (channel) * 64;
|
||||
@@ -548,6 +560,7 @@ static inline void rmt_ll_rx_set_carrier_level(rmt_dev_t *dev, uint32_t channel,
|
||||
* @param mask Event mask
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_enable_interrupt(rmt_dev_t *dev, uint32_t mask, bool enable)
|
||||
{
|
||||
if (enable) {
|
||||
@@ -563,6 +576,7 @@ static inline void rmt_ll_enable_interrupt(rmt_dev_t *dev, uint32_t mask, bool e
|
||||
* @param dev Peripheral instance address
|
||||
* @param mask Interupt status mask
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_clear_interrupt_status(rmt_dev_t *dev, uint32_t mask)
|
||||
{
|
||||
dev->int_clr.val = mask;
|
||||
@@ -586,6 +600,7 @@ static inline volatile void *rmt_ll_get_interrupt_status_reg(rmt_dev_t *dev)
|
||||
* @param channel RMT TX channel number
|
||||
* @return Interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t rmt_ll_tx_get_interrupt_status(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
return dev->int_st.val & RMT_LL_EVENT_TX_MASK(channel);
|
||||
@@ -610,6 +625,7 @@ static inline uint32_t rmt_ll_tx_get_interrupt_status_raw(rmt_dev_t *dev, uint32
|
||||
* @param channel RMT RX channel number
|
||||
* @return Interrupt raw status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t rmt_ll_rx_get_interrupt_status_raw(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
return dev->int_raw.val & (RMT_LL_EVENT_RX_MASK(channel) | RMT_LL_EVENT_RX_ERROR(channel));
|
||||
@@ -622,6 +638,7 @@ static inline uint32_t rmt_ll_rx_get_interrupt_status_raw(rmt_dev_t *dev, uint32
|
||||
* @param channel RMT RX channel number
|
||||
* @return Interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t rmt_ll_rx_get_interrupt_status(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
return dev->int_st.val & RMT_LL_EVENT_RX_MASK(channel);
|
||||
|
@@ -969,6 +969,7 @@ static inline uint32_t spi_ll_slave_get_rcv_bitlen(spi_dev_t *hw)
|
||||
item(SPI_LL_INTR_CMDA, dma_int_ena.cmda, dma_int_raw.cmda, dma_int_clr.cmda=1)
|
||||
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline void spi_ll_enable_intr(spi_dev_t *hw, spi_ll_intr_t intr_mask)
|
||||
{
|
||||
#define ENA_INTR(intr_bit, en_reg, ...) if (intr_mask & (intr_bit)) hw->en_reg = 1;
|
||||
@@ -976,6 +977,7 @@ static inline void spi_ll_enable_intr(spi_dev_t *hw, spi_ll_intr_t intr_mask)
|
||||
#undef ENA_INTR
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline void spi_ll_disable_intr(spi_dev_t *hw, spi_ll_intr_t intr_mask)
|
||||
{
|
||||
#define DIS_INTR(intr_bit, en_reg, ...) if (intr_mask & (intr_bit)) hw->en_reg = 0;
|
||||
@@ -990,6 +992,7 @@ static inline void spi_ll_set_intr(spi_dev_t *hw, spi_ll_intr_t intr_mask)
|
||||
#undef SET_INTR
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline void spi_ll_clear_intr(spi_dev_t *hw, spi_ll_intr_t intr_mask)
|
||||
{
|
||||
#define CLR_INTR(intr_bit, _, __, clr_reg) if (intr_mask & (intr_bit)) hw->clr_reg;
|
||||
@@ -997,6 +1000,7 @@ static inline void spi_ll_clear_intr(spi_dev_t *hw, spi_ll_intr_t intr_mask)
|
||||
#undef CLR_INTR
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline bool spi_ll_get_intr(spi_dev_t *hw, spi_ll_intr_t intr_mask)
|
||||
{
|
||||
#define GET_INTR(intr_bit, _, st_reg, ...) if (intr_mask & (intr_bit) && hw->st_reg) return true;
|
||||
@@ -1142,6 +1146,7 @@ static inline void spi_dma_ll_rx_enable_burst_desc(spi_dma_dev_t *dma_in, uint32
|
||||
* @param channel DMA channel, for chip version compatibility, not used.
|
||||
* @return The address
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t spi_dma_ll_get_in_suc_eof_desc_addr(spi_dma_dev_t *dma_in, uint32_t channel)
|
||||
{
|
||||
return dma_in->dma_in_suc_eof_des_addr;
|
||||
|
@@ -1,5 +1,5 @@
|
||||
/*
|
||||
* SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
|
||||
* SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
@@ -84,6 +84,7 @@ static inline void timer_ll_set_clock_prescale(timg_dev_t *hw, uint32_t timer_nu
|
||||
* @param en True: enable auto reload mode
|
||||
* False: disable auto reload mode
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void timer_ll_enable_auto_reload(timg_dev_t *hw, uint32_t timer_num, bool en)
|
||||
{
|
||||
hw->hw_timer[timer_num].config.tx_autoreload = en;
|
||||
@@ -155,6 +156,7 @@ static inline void timer_ll_set_alarm_value(timg_dev_t *hw, uint32_t timer_num,
|
||||
* @param timer_num Timer number in the group
|
||||
* @param reload_val Reload counter value
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void timer_ll_set_reload_value(timg_dev_t *hw, uint32_t timer_num, uint64_t load_val)
|
||||
{
|
||||
hw->hw_timer[timer_num].loadhi.tx_load_hi = (uint32_t) (load_val >> 32);
|
||||
|
@@ -552,6 +552,7 @@ static inline void adc_ll_set_power_manage(adc_ll_power_t manage)
|
||||
* @param adc_n ADC unit.
|
||||
* @param ctrl ADC controller.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_set_controller(adc_unit_t adc_n, adc_ll_controller_t ctrl)
|
||||
{
|
||||
if (adc_n == ADC_UNIT_1) {
|
||||
@@ -601,6 +602,7 @@ static inline void adc_ll_set_controller(adc_unit_t adc_n, adc_ll_controller_t c
|
||||
*
|
||||
* @param mode Refer to `adc_arbiter_mode_t`.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_set_arbiter_work_mode(adc_arbiter_mode_t mode)
|
||||
{
|
||||
if (mode == ADC_ARB_MODE_FIX) {
|
||||
@@ -627,6 +629,7 @@ static inline void adc_ll_set_arbiter_work_mode(adc_arbiter_mode_t mode)
|
||||
* @param pri_dig Digital controller priority. Range: 0 ~ 2.
|
||||
* @param pri_pwdet Wi-Fi controller priority. Range: 0 ~ 2.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
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) {
|
||||
@@ -689,6 +692,7 @@ static inline void adc_ll_disable_sleep_controller(void)
|
||||
/**
|
||||
* @brief Set common calibration configuration. Should be shared with other parts (PWDET).
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_calibration_init(adc_unit_t adc_n)
|
||||
{
|
||||
if (adc_n == ADC_UNIT_1) {
|
||||
@@ -749,6 +753,7 @@ static inline void adc_ll_calibration_finish(adc_unit_t adc_n)
|
||||
*
|
||||
* @param adc_n ADC index number.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void adc_ll_set_calibration_param(adc_unit_t adc_n, uint32_t param)
|
||||
{
|
||||
uint8_t msb = param >> 8;
|
||||
@@ -1051,6 +1056,7 @@ static inline void adc_oneshot_ll_set_atten(adc_unit_t adc_n, adc_channel_t chan
|
||||
* @param channel ADCn channel number.
|
||||
* @return atten The attenuation option.
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline adc_atten_t adc_ll_get_atten(adc_unit_t adc_n, adc_channel_t channel)
|
||||
{
|
||||
if (adc_n == ADC_UNIT_1) {
|
||||
|
@@ -21,6 +21,7 @@
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t dedic_gpio_cpu_ll_read_in(void)
|
||||
{
|
||||
uint32_t value = 0;
|
||||
@@ -28,6 +29,7 @@ static inline uint32_t dedic_gpio_cpu_ll_read_in(void)
|
||||
return value;
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t dedic_gpio_cpu_ll_read_out(void)
|
||||
{
|
||||
uint32_t value = 0;
|
||||
@@ -35,11 +37,13 @@ static inline uint32_t dedic_gpio_cpu_ll_read_out(void)
|
||||
return value;
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline void dedic_gpio_cpu_ll_write_all(uint32_t value)
|
||||
{
|
||||
asm volatile("wur.gpio_out %0"::"r"(value):);
|
||||
}
|
||||
|
||||
__attribute__((always_inline))
|
||||
static inline void dedic_gpio_cpu_ll_write_mask(uint32_t mask, uint32_t value)
|
||||
{
|
||||
asm volatile("ee.wr_mask_gpio_out %0, %1" : : "r"(value), "r"(mask):);
|
||||
|
@@ -96,6 +96,7 @@ static inline void gpio_ll_set_intr_type(gpio_dev_t *hw, uint32_t gpio_num, gpio
|
||||
* @param core_id interrupt core id
|
||||
* @param status interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_get_intr_status(gpio_dev_t *hw, uint32_t core_id, uint32_t *status)
|
||||
{
|
||||
// On ESP32S3, pcpu_int register represents GPIO0-31 interrupt status on both cores
|
||||
@@ -110,6 +111,7 @@ static inline void gpio_ll_get_intr_status(gpio_dev_t *hw, uint32_t core_id, uin
|
||||
* @param core_id interrupt core id
|
||||
* @param status interrupt status high
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_get_intr_status_high(gpio_dev_t *hw, uint32_t core_id, uint32_t *status)
|
||||
{
|
||||
// On ESP32S3, pcpu_int1 register represents GPIO32-48 interrupt status on both cores
|
||||
@@ -123,6 +125,7 @@ static inline void gpio_ll_get_intr_status_high(gpio_dev_t *hw, uint32_t core_id
|
||||
* @param hw Peripheral GPIO hardware instance address.
|
||||
* @param mask interrupt status clear mask
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_clear_intr_status(gpio_dev_t *hw, uint32_t mask)
|
||||
{
|
||||
hw->status_w1tc = mask;
|
||||
@@ -134,6 +137,7 @@ static inline void gpio_ll_clear_intr_status(gpio_dev_t *hw, uint32_t mask)
|
||||
* @param hw Peripheral GPIO hardware instance address.
|
||||
* @param mask interrupt status high clear mask
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_clear_intr_status_high(gpio_dev_t *hw, uint32_t mask)
|
||||
{
|
||||
hw->status1_w1tc.intr_st = mask;
|
||||
@@ -146,6 +150,7 @@ static inline void gpio_ll_clear_intr_status_high(gpio_dev_t *hw, uint32_t mask)
|
||||
* @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);
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_intr_enable_on_core(gpio_dev_t *hw, uint32_t core_id, uint32_t gpio_num)
|
||||
{
|
||||
(void)core_id;
|
||||
@@ -158,6 +163,7 @@ static inline void gpio_ll_intr_enable_on_core(gpio_dev_t *hw, uint32_t core_id,
|
||||
* @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);
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_intr_disable(gpio_dev_t *hw, uint32_t gpio_num)
|
||||
{
|
||||
hw->pin[gpio_num].int_ena = 0; //disable GPIO intr
|
||||
@@ -248,6 +254,7 @@ static inline void gpio_ll_od_enable(gpio_dev_t *hw, uint32_t gpio_num)
|
||||
* @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
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void gpio_ll_set_level(gpio_dev_t *hw, uint32_t gpio_num, uint32_t level)
|
||||
{
|
||||
if (level) {
|
||||
|
@@ -89,6 +89,7 @@ static inline void pcnt_ll_set_level_action(pcnt_dev_t *hw, uint32_t unit, uint3
|
||||
* @param unit Pulse Counter unit number
|
||||
* @return PCNT count value (a signed integer)
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline int pcnt_ll_get_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
{
|
||||
pcnt_un_cnt_reg_t cnt_reg = hw->cnt_unit[unit];
|
||||
@@ -102,6 +103,7 @@ static inline int pcnt_ll_get_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
* @param hw Peripheral PCNT hardware instance address.
|
||||
* @param unit PCNT unit number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void pcnt_ll_stop_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
{
|
||||
hw->ctrl.val |= 1 << (2 * unit + 1);
|
||||
@@ -113,6 +115,7 @@ static inline void pcnt_ll_stop_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
* @param hw Peripheral PCNT hardware instance address.
|
||||
* @param unit PCNT unit number, select from uint32_t
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void pcnt_ll_start_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
{
|
||||
hw->ctrl.val &= ~(1 << (2 * unit + 1));
|
||||
@@ -124,6 +127,7 @@ static inline void pcnt_ll_start_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
* @param hw Peripheral PCNT hardware instance address.
|
||||
* @param unit PCNT unit number, select from uint32_t
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void pcnt_ll_clear_count(pcnt_dev_t *hw, uint32_t unit)
|
||||
{
|
||||
hw->ctrl.val |= 1 << (2 * unit);
|
||||
|
@@ -148,6 +148,7 @@ static inline void rmt_ll_tx_set_channel_clock_div(rmt_dev_t *dev, uint32_t chan
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT TX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_reset_pointer(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
dev->chnconf0[channel].mem_rd_rst_chn = 1;
|
||||
@@ -175,6 +176,7 @@ static inline void rmt_ll_tx_enable_dma(rmt_dev_t *dev, uint32_t channel, bool e
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT TX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_start(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
// update other configuration registers before start transmitting
|
||||
@@ -188,6 +190,7 @@ static inline void rmt_ll_tx_start(rmt_dev_t *dev, uint32_t channel)
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT TX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_stop(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
dev->chnconf0[channel].tx_stop_chn = 1;
|
||||
@@ -226,6 +229,7 @@ static inline void rmt_ll_tx_enable_wrap(rmt_dev_t *dev, uint32_t channel, bool
|
||||
* @param channel RMT TX channel number
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_enable_loop(rmt_dev_t *dev, uint32_t channel, bool enable)
|
||||
{
|
||||
dev->chnconf0[channel].tx_conti_mode_chn = enable;
|
||||
@@ -238,6 +242,7 @@ static inline void rmt_ll_tx_enable_loop(rmt_dev_t *dev, uint32_t channel, bool
|
||||
* @param channel RMT TX channel number
|
||||
* @param count TX loop count
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_set_loop_count(rmt_dev_t *dev, uint32_t channel, uint32_t count)
|
||||
{
|
||||
HAL_ASSERT(count <= RMT_LL_MAX_LOOP_COUNT_PER_BATCH && "loop count out of range");
|
||||
@@ -250,6 +255,7 @@ static inline void rmt_ll_tx_set_loop_count(rmt_dev_t *dev, uint32_t channel, ui
|
||||
* @param dev Peripheral instance address
|
||||
* @param channel RMT TX channel number
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_reset_loop_count(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
dev->chn_tx_lim[channel].loop_count_reset_chn = 1;
|
||||
@@ -263,6 +269,7 @@ static inline void rmt_ll_tx_reset_loop_count(rmt_dev_t *dev, uint32_t channel)
|
||||
* @param channel RMT TX channel number
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_enable_loop_count(rmt_dev_t *dev, uint32_t channel, bool enable)
|
||||
{
|
||||
dev->chn_tx_lim[channel].tx_loop_cnt_en_chn = enable;
|
||||
@@ -275,6 +282,7 @@ static inline void rmt_ll_tx_enable_loop_count(rmt_dev_t *dev, uint32_t channel,
|
||||
* @param channel RMT TX channel number
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_enable_loop_autostop(rmt_dev_t *dev, uint32_t channel, bool enable)
|
||||
{
|
||||
dev->chn_tx_lim[channel].loop_stop_en_chn = enable;
|
||||
@@ -331,6 +339,7 @@ static inline void rmt_ll_tx_sync_group_remove_channels(rmt_dev_t *dev, uint32_t
|
||||
* @param level IDLE level (1 => high, 0 => low)
|
||||
* @param enable True to fix the IDLE level, otherwise the IDLE level is determined by EOF encoder
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_tx_fix_idle_level(rmt_dev_t *dev, uint32_t channel, uint8_t level, bool enable)
|
||||
{
|
||||
dev->chnconf0[channel].idle_out_en_chn = enable;
|
||||
@@ -471,6 +480,7 @@ static inline void rmt_ll_rx_enable_dma(rmt_dev_t *dev, uint32_t channel, bool e
|
||||
* @param channel RMT RX channel number
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_rx_enable(rmt_dev_t *dev, uint32_t channel, bool enable)
|
||||
{
|
||||
dev->chmconf[channel].conf1.rx_en_chm = enable;
|
||||
@@ -509,6 +519,7 @@ static inline void rmt_ll_rx_set_idle_thres(rmt_dev_t *dev, uint32_t channel, ui
|
||||
* @param channel RMT RX channel number
|
||||
* @param owner Memory owner
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_rx_set_mem_owner(rmt_dev_t *dev, uint32_t channel, rmt_ll_mem_owner_t owner)
|
||||
{
|
||||
dev->chmconf[channel].conf1.mem_owner_chm = owner;
|
||||
@@ -545,6 +556,7 @@ static inline void rmt_ll_rx_set_filter_thres(rmt_dev_t *dev, uint32_t channel,
|
||||
* @param channel RMT RX channel number
|
||||
* @return writer offset
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t rmt_ll_rx_get_memory_writer_offset(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
return dev->chmstatus[channel].mem_waddr_ex_chm - (channel + 4) * 48;
|
||||
@@ -622,6 +634,7 @@ static inline void rmt_ll_rx_enable_wrap(rmt_dev_t *dev, uint32_t channel, bool
|
||||
* @param mask Event mask
|
||||
* @param enable True to enable, False to disable
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_enable_interrupt(rmt_dev_t *dev, uint32_t mask, bool enable)
|
||||
{
|
||||
if (enable) {
|
||||
@@ -637,6 +650,7 @@ static inline void rmt_ll_enable_interrupt(rmt_dev_t *dev, uint32_t mask, bool e
|
||||
* @param dev Peripheral instance address
|
||||
* @param mask Interupt status mask
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void rmt_ll_clear_interrupt_status(rmt_dev_t *dev, uint32_t mask)
|
||||
{
|
||||
dev->int_clr.val = mask;
|
||||
@@ -660,6 +674,7 @@ static inline volatile void *rmt_ll_get_interrupt_status_reg(rmt_dev_t *dev)
|
||||
* @param channel RMT TX channel number
|
||||
* @return Interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t rmt_ll_tx_get_interrupt_status(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
return dev->int_st.val & RMT_LL_EVENT_TX_MASK(channel);
|
||||
@@ -696,6 +711,7 @@ static inline uint32_t rmt_ll_rx_get_interrupt_status_raw(rmt_dev_t *dev, uint32
|
||||
* @param channel RMT RX channel number
|
||||
* @return Interrupt status
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline uint32_t rmt_ll_rx_get_interrupt_status(rmt_dev_t *dev, uint32_t channel)
|
||||
{
|
||||
return dev->int_st.val & RMT_LL_EVENT_RX_MASK(channel);
|
||||
|
@@ -1,5 +1,5 @@
|
||||
/*
|
||||
* SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
|
||||
* SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
@@ -83,6 +83,7 @@ static inline void timer_ll_set_clock_prescale(timg_dev_t *hw, uint32_t timer_nu
|
||||
* @param en True: enable auto reload mode
|
||||
* False: disable auto reload mode
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void timer_ll_enable_auto_reload(timg_dev_t *hw, uint32_t timer_num, bool en)
|
||||
{
|
||||
hw->hw_timer[timer_num].config.tn_autoreload = en;
|
||||
@@ -154,6 +155,7 @@ static inline void timer_ll_set_alarm_value(timg_dev_t *hw, uint32_t timer_num,
|
||||
* @param timer_num Timer number in the group
|
||||
* @param reload_val Reload counter value
|
||||
*/
|
||||
__attribute__((always_inline))
|
||||
static inline void timer_ll_set_reload_value(timg_dev_t *hw, uint32_t timer_num, uint64_t reload_val)
|
||||
{
|
||||
hw->hw_timer[timer_num].loadhi.tn_load_hi = (uint32_t)(reload_val >> 32);
|
||||
|
@@ -30,11 +30,13 @@ entries:
|
||||
lcd_hal: lcd_hal_cal_pclk_freq (noflash)
|
||||
if ADC_ONESHOT_CTRL_FUNC_IN_IRAM = y:
|
||||
adc_oneshot_hal (noflash)
|
||||
adc_hal_common: adc_hal_calibration_init (noflash)
|
||||
adc_hal_common: adc_hal_set_calibration_param (noflash)
|
||||
adc_hal_common: get_controller (noflash)
|
||||
adc_hal_common: adc_hal_set_controller (noflash)
|
||||
if SOC_ADC_ARBITER_SUPPORTED = y:
|
||||
adc_hal_common: adc_hal_arbiter_config (noflash)
|
||||
if SOC_ADC_CALIBRATION_V1_SUPPORTED = y:
|
||||
adc_hal_common: adc_hal_set_calibration_param (noflash)
|
||||
adc_hal_common: adc_hal_calibration_init (noflash)
|
||||
if ADC_CONTINUOUS_ISR_IRAM_SAFE = y:
|
||||
adc_hal: adc_hal_get_reading_result (noflash)
|
||||
adc_hal: adc_hal_digi_start (noflash)
|
||||
|
Reference in New Issue
Block a user