fix(drivers): fix typos found by codespell

codespell components/esp_driver*
pull/13550/head
morris 2024-03-25 14:11:33 +08:00
rodzic 2ee266c0d6
commit c0289ee6eb
131 zmienionych plików z 327 dodań i 327 usunięć

Wyświetl plik

@ -16,7 +16,7 @@ set(includes "deprecated"
# Always included linker fragments
set(ldfragments "")
# ADC related source files (dprecated)
# ADC related source files (deprecated)
if(CONFIG_SOC_ADC_SUPPORTED)
list(APPEND srcs "deprecated/adc_legacy.c")
endif()

Wyświetl plik

@ -18,7 +18,7 @@ menu "Driver Configurations"
bool "Suppress legacy driver deprecated warning"
default n
help
Wether to suppress the deprecation warnings when using legacy adc driver (driver/adc.h).
Whether to suppress the deprecation warnings when using legacy adc driver (driver/adc.h).
If you want to continue using the legacy driver, and don't want to see related deprecation warnings,
you can enable this option.
@ -55,7 +55,7 @@ menu "Driver Configurations"
bool "Suppress legacy driver deprecated warning"
default n
help
Wether to suppress the deprecation warnings when using legacy adc calibration
Whether to suppress the deprecation warnings when using legacy adc calibration
driver (esp_adc_cal.h).
If you want to continue using the legacy driver, and don't want to see related
deprecation warnings, you can enable this option.
@ -69,7 +69,7 @@ menu "Driver Configurations"
bool "Suppress legacy driver deprecated warning"
default n
help
Wether to suppress the deprecation warnings when using legacy MCPWM driver (driver/mcpwm.h).
Whether to suppress the deprecation warnings when using legacy MCPWM driver (driver/mcpwm.h).
If you want to continue using the legacy driver, and don't want to see related deprecation warnings,
you can enable this option.
endmenu # Legacy MCPWM Driver Configurations
@ -80,7 +80,7 @@ menu "Driver Configurations"
bool "Suppress legacy driver deprecated warning"
default n
help
Wether to suppress the deprecation warnings when using legacy timer group driver (driver/timer.h).
Whether to suppress the deprecation warnings when using legacy timer group driver (driver/timer.h).
If you want to continue using the legacy driver, and don't want to see related deprecation warnings,
you can enable this option.
@ -92,7 +92,7 @@ menu "Driver Configurations"
bool "Suppress legacy driver deprecated warning"
default n
help
Wether to suppress the deprecation warnings when using legacy rmt driver (driver/rmt.h).
Whether to suppress the deprecation warnings when using legacy rmt driver (driver/rmt.h).
If you want to continue using the legacy driver, and don't want to see related deprecation warnings,
you can enable this option.
endmenu # Legacy RMT Driver Configurations

Wyświetl plik

@ -126,7 +126,7 @@ typedef struct adc_digi_context_t {
RingbufHandle_t ringbuf_hdl; //RX ringbuffer handler
intptr_t rx_eof_desc_addr; //eof descriptor address of RX channel
bool ringbuf_overflow_flag; //1: ringbuffer overflow
bool driver_start_flag; //1: driver is started; 0: driver is stoped
bool driver_start_flag; //1: driver is started; 0: driver is stopped
bool use_adc1; //1: ADC unit1 will be used; 0: ADC unit1 won't be used.
bool use_adc2; //1: ADC unit2 will be used; 0: ADC unit2 won't be used. This determines whether to acquire sar_adc2_mutex lock or not.
adc_atten_t adc1_atten; //Attenuation for ADC1. On this chip each ADC can only support one attenuation.

Wyświetl plik

@ -5,7 +5,7 @@
*/
/*----------------------------------------------------------------------------------
This file contains ESP32 and ESP32S2 Depricated ADC APIs and functions
This file contains ESP32 and ESP32S2 Deprecated ADC APIs and functions
-----------------------------------------------------------------------------------*/
#include "sdkconfig.h"
@ -52,7 +52,7 @@ esp_pm_lock_handle_t adc_digi_arbiter_lock = NULL;
#if CONFIG_IDF_TARGET_ESP32
/*---------------------------------------------------------------
ESP32 Depricated ADC APIs and functions
ESP32 Deprecated ADC APIs and functions
---------------------------------------------------------------*/
#define DIG_ADC_OUTPUT_FORMAT_DEFUALT (ADC_DIGI_FORMAT_12BIT)
#define DIG_ADC_ATTEN_DEFUALT (ADC_ATTEN_DB_12)

Wyświetl plik

@ -879,7 +879,7 @@ static void adc_hal_onetime_start(adc_unit_t adc_n, uint32_t clk_src_freq_hz)
esp_rom_delay_us(delay);
adc_oneshot_ll_start(true);
//No need to delay here. Becuase if the start signal is not seen, there won't be a done intr.
//No need to delay here. Because if the start signal is not seen, there won't be a done intr.
#else
(void)clk_src_freq_hz;
adc_oneshot_ll_start(adc_n);

Wyświetl plik

@ -285,7 +285,7 @@ esp_err_t adc_vref_to_gpio(adc_unit_t adc_unit, gpio_num_t gpio);
/**
* @brief Initialize the Digital ADC.
*
* @param init_config Pointer to Digital ADC initilization config. Refer to ``adc_digi_init_config_t``.
* @param init_config Pointer to Digital ADC initialization config. Refer to ``adc_digi_init_config_t``.
*
* @return
* - ESP_ERR_INVALID_ARG If the combination of arguments is invalid.
@ -340,7 +340,7 @@ esp_err_t adc_digi_deinitialize(void);
/**
* @brief Setting the digital controller.
*
* @param config Pointer to digital controller paramter. Refer to ``adc_digi_config_t``.
* @param config Pointer to digital controller parameter. Refer to ``adc_digi_config_t``.
*
* @return
* - ESP_ERR_INVALID_STATE Driver state is invalid.

Wyświetl plik

@ -129,7 +129,7 @@ esp_err_t dac_digi_deinit(void);
/**
* @brief Setting the DAC digital controller.
*
* @param cfg Pointer to digital controller paramter. See ``dac_digi_config_t``.
* @param cfg Pointer to digital controller parameter. See ``dac_digi_config_t``.
*
* @return
* - ESP_OK success

Wyświetl plik

@ -276,7 +276,7 @@ esp_err_t i2s_zero_dma_buffer(i2s_port_t i2s_num);
*
* @param i2s_num I2S port number
*
* @param pcm_cfg including mode selection and a/u-law decompress or compress configuration paramater
* @param pcm_cfg including mode selection and a/u-law decompress or compress configuration parameter
*
* @return
* - ESP_OK Success

Wyświetl plik

@ -51,7 +51,7 @@ typedef enum {
#if SOC_I2S_SUPPORTS_TDM
// Bit map of activated chan.
// There are 16 channels in TDM mode.
// For TX module, only the activated channel send the audio data, the unactivated channel send a constant(configurable) or will be skiped if 'skip_msk' is set.
// For TX module, only the activated channel send the audio data, the unactivated channel send a constant(configurable) or will be skipped if 'skip_msk' is set.
// For RX module, only receive the audio data in activated channels, the data in unactivated channels will be ignored.
// the bit map of activated channel can not exceed the maximum enabled channel number (i.e. 0x10000 << total_chan_num).
// e.g: active_chan_mask = (I2S_TDM_ACTIVE_CH0 | I2S_TDM_ACTIVE_CH3), here the active_chan_number is 2 and total_chan_num is not supposed to be smaller than 4.

Wyświetl plik

@ -215,7 +215,7 @@ esp_err_t timer_isr_callback_remove(timer_group_t group_num, timer_idx_t timer_n
* @param handle Pointer to return handle. If non-NULL, a handle for the interrupt will
* be returned here.
*
* @note If use this function to reigster ISR, you need to write the whole ISR.
* @note If use this function to register ISR, you need to write the whole ISR.
* In the interrupt handler, you need to call timer_spinlock_take(..) before
* your handling, and call timer_spinlock_give(...) after your handling.
*

Wyświetl plik

@ -115,7 +115,7 @@ typedef int timer_src_clk_t;
* - False Not do task yield at the end of ISR
*
* @note If you called FreeRTOS functions in callback, you need to return true or false based on
* the retrun value of argument `pxHigherPriorityTaskWoken`.
* the return value of argument `pxHigherPriorityTaskWoken`.
* For example, `xQueueSendFromISR` is called in callback, if the return value `pxHigherPriorityTaskWoken`
* of any FreeRTOS calls is pdTRUE, return true; otherwise return false.
*/

Wyświetl plik

@ -534,7 +534,7 @@ static inline uint32_t i2s_get_buf_size(i2s_port_t i2s_num)
}
}
if (bufsize / bytes_per_frame != p_i2s[i2s_num]->dma_frame_num) {
ESP_LOGW(TAG, "dma frame num is adjusted to %"PRIu32" to algin the dma buffer with %"PRIu32
ESP_LOGW(TAG, "dma frame num is adjusted to %"PRIu32" to align the dma buffer with %"PRIu32
", bufsize = %"PRIu32, bufsize / bytes_per_frame, alignment, bufsize);
}
#else
@ -626,7 +626,7 @@ static esp_err_t i2s_realloc_dma_buffer(i2s_port_t i2s_num, i2s_dma_t *dma_obj)
static esp_err_t i2s_destroy_dma_object(i2s_port_t i2s_num, i2s_dma_t **dma)
{
/* Check if DMA truely need destroy */
/* Check if DMA truly need destroy */
ESP_RETURN_ON_FALSE(p_i2s[i2s_num], ESP_ERR_INVALID_ARG, TAG, "I2S not initialized yet");
if (!(*dma)) {
return ESP_OK;
@ -662,7 +662,7 @@ static esp_err_t i2s_create_dma_object(i2s_port_t i2s_num, i2s_dma_t **dma)
/* Allocate new DMA structure */
*dma = (i2s_dma_t *) calloc(1, sizeof(i2s_dma_t));
ESP_RETURN_ON_FALSE(*dma, ESP_ERR_NO_MEM, TAG, "DMA object allocate failed");
/* Allocate DMA buffer poiter */
/* Allocate DMA buffer pointer */
(*dma)->buf = (char **)heap_caps_calloc(buf_cnt, sizeof(char *), MALLOC_CAP_DMA);
if (!(*dma)->buf) {
goto err;
@ -1536,7 +1536,7 @@ static esp_err_t i2s_init_legacy(i2s_port_t i2s_num, int intr_alloc_flag)
i2s_set_slot_legacy(i2s_num);
i2s_set_clock_legacy(i2s_num);
ESP_RETURN_ON_ERROR(i2s_dma_intr_init(i2s_num, intr_alloc_flag), TAG, "I2S interrupt initailze failed");
ESP_RETURN_ON_ERROR(i2s_dma_intr_init(i2s_num, intr_alloc_flag), TAG, "I2S interrupt initialize failed");
ESP_RETURN_ON_ERROR(i2s_dma_object_init(i2s_num), TAG, "I2S dma object create failed");
if (p_i2s[i2s_num]->dir & I2S_DIR_TX) {
ESP_RETURN_ON_ERROR(i2s_realloc_dma_buffer(i2s_num, p_i2s[i2s_num]->tx), TAG, "Allocate I2S dma tx buffer failed");
@ -1656,7 +1656,7 @@ esp_err_t i2s_driver_install(i2s_port_t i2s_num, const i2s_config_t *i2s_config,
p_i2s[i2s_num] = i2s_obj;
i2s_hal_init(&i2s_obj->hal, i2s_num);
/* Step 3: Store and assign configarations */
/* Step 3: Store and assign configurations */
i2s_mode_identify(i2s_num, i2s_config);
ESP_GOTO_ON_ERROR(i2s_config_transfer(i2s_num, i2s_config), err, TAG, "I2S install failed");
i2s_obj->dma_desc_num = i2s_config->dma_desc_num;
@ -1948,7 +1948,7 @@ esp_err_t i2s_set_pin(i2s_port_t i2s_num, const i2s_pin_config_t *pin)
}
}
/* Set data input/ouput GPIO */
/* Set data input/output GPIO */
gpio_matrix_out_check_and_set(pin->data_out_num, i2s_periph_signal[i2s_num].data_out_sig, 0, 0);
gpio_matrix_in_check_and_set(pin->data_in_num, i2s_periph_signal[i2s_num].data_in_sig, 0);
return ESP_OK;

Wyświetl plik

@ -850,7 +850,7 @@ esp_err_t mcpwm_capture_enable_channel(mcpwm_unit_t mcpwm_num, mcpwm_capture_cha
MCPWM_CAP_EXIST_ERROR);
mcpwm_hal_context_t *hal = &context[mcpwm_num].hal;
// enable MCPWM module incase user don't use `mcpwm_init` at all. always increase reference count
// enable MCPWM module in case user don't use `mcpwm_init` at all. always increase reference count
mcpwm_module_enable(mcpwm_num);
mcpwm_hal_init_config_t init_config = {

Wyświetl plik

@ -368,7 +368,7 @@ static inline esp_err_t _pcnt_unit_config(pcnt_port_t pcnt_port, const pcnt_conf
PCNT_CHECK(ctrl_io < 0 || GPIO_IS_VALID_GPIO(ctrl_io), "PCNT ctrl io error", ESP_ERR_INVALID_ARG);
PCNT_CHECK((pcnt_config->pos_mode < PCNT_COUNT_MAX) && (pcnt_config->neg_mode < PCNT_COUNT_MAX), PCNT_COUNT_MODE_ERR_STR, ESP_ERR_INVALID_ARG);
PCNT_CHECK((pcnt_config->hctrl_mode < PCNT_MODE_MAX) && (pcnt_config->lctrl_mode < PCNT_MODE_MAX), PCNT_CTRL_MODE_ERR_STR, ESP_ERR_INVALID_ARG);
/*Enalbe hardware module*/
/*Enable hardware module*/
static bool pcnt_enable = false;
if (pcnt_enable == false) {
PCNT_RCC_ATOMIC() {

Wyświetl plik

@ -679,7 +679,7 @@ static esp_err_t rmt_internal_config(rmt_dev_t *dev, const rmt_config_t *rmt_par
#endif
RMT_EXIT_CRITICAL();
ESP_LOGD(TAG, "Rmt Rx Channel %u|Gpio %u|Sclk_Hz %"PRIu32"|Div %u|Thresold %u|Filter %u",
ESP_LOGD(TAG, "Rmt Rx Channel %u|Gpio %u|Sclk_Hz %"PRIu32"|Div %u|Threshold %u|Filter %u",
channel, gpio_num, rmt_source_clk_hz, clk_div, threshold, filter_cnt);
}

Wyświetl plik

@ -217,7 +217,7 @@ static void IRAM_ATTR timer_isr_default(void *arg)
timer_ll_clear_intr_status(hal->dev, TIMER_LL_EVENT_ALARM(timer_id));
// call user registered callback
is_awoken = timer_obj->timer_isr_fun.fn(timer_obj->timer_isr_fun.args);
// reenable alarm if required
// re-enable alarm if required
uint64_t new_alarm_value = timer_obj->alarm_value;
bool reenable_alarm = (new_alarm_value != old_alarm_value) || timer_obj->auto_reload_en;
timer_ll_enable_alarm(hal->dev, timer_id, reenable_alarm);

Wyświetl plik

@ -1198,7 +1198,7 @@ static esp_err_t i2c_cmd_allocate(i2c_cmd_desc_t *cmd_desc, size_t n, size_t siz
/* Allocate the pointer. */
*outptr = cmd_desc->free_buffer;
/* Decrement the free size from the user's bufffer. */
/* Decrement the free size from the user's buffer. */
cmd_desc->free_buffer += required;
cmd_desc->free_size -= required;
}

Wyświetl plik

@ -27,7 +27,7 @@ extern "C" {
#endif
// I2C clk flags for users to use, can be expanded in the future.
#define I2C_SCLK_SRC_FLAG_FOR_NOMAL (0) /*!< Any one clock source that is available for the specified frequency may be choosen*/
#define I2C_SCLK_SRC_FLAG_FOR_NOMAL (0) /*!< Any one clock source that is available for the specified frequency may be chosen*/
#define I2C_SCLK_SRC_FLAG_AWARE_DFS (1 << 0) /*!< For REF tick clock, it won't change with APB.*/
#define I2C_SCLK_SRC_FLAG_LIGHT_SLEEP (1 << 1) /*!< For light sleep mode.*/
@ -606,7 +606,7 @@ esp_err_t i2c_get_timeout(i2c_port_t i2c_num, int *timeout);
*
* @param i2c_num I2C port number
* @param tx_trans_mode I2C sending data mode
* @param rx_trans_mode I2C receving data mode
* @param rx_trans_mode I2C receiving data mode
*
* @return
* - ESP_OK Success

Wyświetl plik

@ -295,7 +295,7 @@ esp_err_t essl_sdio_send_packet(void *arg, const void *start, size_t length, uin
const int block_size = 512;
/* Though the driver supports to split packet of unaligned size into
* length of 4x and 1~3, we still send aligned size of data to get
* higher effeciency. The length is determined by the SDIO address, and
* higher efficiency. The length is determined by the SDIO address, and
* the remainning will be discard by the slave hardware.
*/
int block_n = len_remain / block_size;
@ -348,7 +348,7 @@ esp_err_t essl_sdio_get_packet(void *arg, void *out_data, size_t size, uint32_t
len_to_send = len_remain;
/* though the driver supports to split packet of unaligned size into length
* of 4x and 1~3, we still get aligned size of data to get higher
* effeciency. The length is determined by the SDIO address, and the
* efficiency. The length is determined by the SDIO address, and the
* remainning will be ignored by the slave hardware.
*/
err = sdmmc_io_read_bytes(ctx->card, 1, ESSL_CMD53_END_ADDR - len_remain, start, (len_to_send + 3) & (~3));
@ -413,7 +413,7 @@ esp_err_t essl_sdio_update_rx_data_size(void *arg, uint32_t wait_ms)
esp_err_t essl_sdio_write_reg(void *arg, uint8_t addr, uint8_t value, uint8_t *value_o, uint32_t wait_ms)
{
ESP_LOGV(TAG, "write_reg: 0x%02"PRIX8, value);
// addrress over range
// address over range
if (addr >= 60) {
return ESP_ERR_INVALID_ARG;
}

Wyświetl plik

@ -39,7 +39,7 @@ typedef struct {
/* Master TX, Slave RX */
struct {
size_t sent_buf_num; // Number of TX buffers that has been sent out by the master.
size_t slave_rx_buf_num; // Number of RX buffers laoded by the slave.
size_t slave_rx_buf_num; // Number of RX buffers loaded by the slave.
uint16_t tx_buffer_size; /* Buffer size for Master TX / Slave RX direction.
* Data with length within this size will still be regarded as one buffer.
* E.g. 10 bytes data costs 2 buffers if the size is 8 bytes per buffer. */

Wyświetl plik

@ -46,7 +46,7 @@ esp_err_t essl_sdio_init_dev(essl_handle_t *out_handle, const essl_sdio_config_t
*/
esp_err_t essl_sdio_deinit_dev(essl_handle_t handle);
//Please call `essl_` functions witout `sdio` instead of calling these functions directly.
//Please call `essl_` functions without `sdio` instead of calling these functions directly.
/** @cond */
/**
* SDIO Initialize process of an ESSL SDIO slave device.

Wyświetl plik

@ -261,7 +261,7 @@ esp_err_t spitest_check_data(int len, spi_transaction_t *master_t, slave_rxdata_
int r = memcmp(expected, actual, len);\
if (r != 0) {\
ESP_LOG_BUFFER_HEXDUMP("actual ", actual, len, ESP_LOG_WARN);\
ESP_LOG_BUFFER_HEXDUMP("expecte", expected, len, ESP_LOG_INFO);\
ESP_LOG_BUFFER_HEXDUMP("expected", expected, len, ESP_LOG_INFO);\
TEST_ASSERT_EQUAL_HEX8_ARRAY(expected, actual, len);\
}\
r;\
@ -278,10 +278,10 @@ static inline int get_trans_len(spi_dup_t dup, spi_transaction_t *master_t)
//remove device from bus and free the bus
void master_free_device_bus(spi_device_handle_t spi);
//use this function to fix the output source when assign multiple funcitons to a same pin
//use this function to fix the output source when assign multiple functions to a same pin
void spitest_gpio_output_sel(uint32_t gpio_num, int func, uint32_t signal_idx);
//use this function to fix the input source when assign multiple funcitons to a same pin
//use this function to fix the input source when assign multiple functions to a same pin
void spitest_gpio_input_sel(uint32_t gpio_num, int func, uint32_t signal_idx);
//Note this cs_num is the ID of the connected devices' ID, e.g. if 2 devices are connected to the bus,

Wyświetl plik

@ -582,7 +582,7 @@ TEST_CASE("I2S_write_and_read_test_with_master_tx_and_slave_rx", "[i2s_legacy]")
}
length = length + bytes_read;
}
// test the readed data right or not
// test the read data right or not
for (int i = end_position - 99; i <= end_position; i++) {
TEST_ASSERT_EQUAL_UINT8((i - end_position + 100), *(i2s_read_buff + i));
}
@ -687,7 +687,7 @@ TEST_CASE("I2S_write_and_read_test_master_rx_and_slave_tx", "[i2s_legacy]")
}
length = length + bytes_read;
}
// test the readed data right or not
// test the read data right or not
for (int i = end_position - 99; i <= end_position; i++) {
TEST_ASSERT_EQUAL_UINT8((i - end_position + 100), *(i2s_read_buff + i));
}
@ -892,7 +892,7 @@ static void i2s_test_common_sample_rate(i2s_port_t id)
case_cnt = 15;
#endif
// Acquire the PM lock incase Dynamic Frequency Scaling(DFS) lower the frequency
// Acquire the PM lock in case Dynamic Frequency Scaling(DFS) lower the frequency
#ifdef CONFIG_PM_ENABLE
esp_pm_lock_handle_t pm_lock;
esp_pm_lock_type_t pm_type = ESP_PM_APB_FREQ_MAX;
@ -923,7 +923,7 @@ static void i2s_test_common_sample_rate(i2s_port_t id)
TEST_ESP_OK(pcnt_del_unit(pcnt_unit));
}
TEST_CASE("I2S clock freqency test", "[i2s_legacy]")
TEST_CASE("I2S clock frequency test", "[i2s_legacy]")
{
// master driver installed and send data
i2s_config_t master_i2s_config = {

Wyświetl plik

@ -693,7 +693,7 @@ static void i2c_scl_freq_cal(void)
const float i2c_cource_clk_period = 0.0125;
int expt_cnt = 542;
#else
const int i2c_source_clk_freq = 18000000; // Clock sorce: RTC
const int i2c_source_clk_freq = 18000000; // Clock source: RTC
const float i2c_cource_clk_period = 0.056;
int expt_cnt = 540;
#endif

Wyświetl plik

@ -409,7 +409,7 @@ TEST_CASE("PCNT_basic_function_test", "[pcnt]")
produce_pulse();
pcnt_test_io_config(PCNT_CTRL_HIGH_LEVEL);
// initialize first, the initail value should be 0
// initialize first, the initial value should be 0
TEST_ESP_OK(pcnt_counter_pause(PCNT_UNIT_0));
TEST_ESP_OK(pcnt_counter_clear(PCNT_UNIT_0));
TEST_ESP_OK(pcnt_get_counter_value(PCNT_UNIT_0, &test_counter));
@ -511,7 +511,7 @@ TEST_CASE("PCNT_interrupt_method_test_control_IO_high", "[pcnt][timeout=120]")
TEST_ESP_OK(pcnt_event_enable(PCNT_UNIT_0, PCNT_EVT_H_LIM)); // when arrive to max limit trigger
TEST_ESP_OK(pcnt_event_enable(PCNT_UNIT_0, PCNT_EVT_L_LIM)); // when arrive to minimum limit trigger
// initialize first, the initail value should be 0
// initialize first, the initial value should be 0
TEST_ESP_OK(pcnt_counter_pause(PCNT_UNIT_0));
TEST_ESP_OK(pcnt_counter_clear(PCNT_UNIT_0));

Wyświetl plik

@ -627,7 +627,7 @@ TEST_CASE("RMT Interrupt IRAM Safe", "[rmt]")
// install interrupt with IRAM safe
TEST_ESP_OK(rmt_driver_install(tx.channel, 0, ESP_INTR_FLAG_IRAM));
// send a large buffer, ensure the RMT hardware is still in work when we disable the flash cache afterwords
// send a large buffer, ensure the RMT hardware is still in work when we disable the flash cache afterwards
rmt_item32_t items[256] = {};
for (int i = 0; i < 256; i++) {
items[i].level0 = 0;

Wyświetl plik

@ -841,7 +841,7 @@ TEST_CASE("Timer_interrupt_register", "[hw_timer]")
#endif
vTaskDelay(1000 / portTICK_PERIOD_MS);
// ISR hanlde function should be free before next ISR register.
// ISR handle function should be free before next ISR register.
for (uint32_t tg_idx = 0; tg_idx < TIMER_GROUP_MAX; tg_idx++) {
for (uint32_t timer_idx = 0; timer_idx < TIMER_MAX; timer_idx++) {
TEST_ESP_OK(esp_intr_free(timer_isr_handle[tg_idx * SOC_TIMER_GROUP_TIMERS_PER_GROUP + timer_idx]));

Wyświetl plik

@ -409,7 +409,7 @@ TEST_CASE("Touch Sensor reading test (SW, Timer, filter)", "[touch]")
}
/*
* Test the base patameter mode.
* Test the base parameter mode.
* TEST POINT:
* 1. measure time and sleep time setting.
* 2. Charge / incharge voltage threshold setting.
@ -1287,7 +1287,7 @@ esp_err_t test_touch_filter_parameter_jitter(int jitter_step)
return ESP_OK;
}
TEST_CASE("Touch Sensor filter paramter test (debounce, reset, jitter)", "[touch]")
TEST_CASE("Touch Sensor filter parameter test (debounce, reset, jitter)", "[touch]")
{
ESP_LOGI(TAG, "*********** touch filter debounce test ********************");
TEST_ESP_OK(test_touch_filter_parameter_debounce(0));
@ -1994,7 +1994,7 @@ TEST_CASE("Touch Sensor sleep pad wakeup deep sleep test", "[touch][ignore]")
#include "touch_scope.h"
/*
* 0: 10 channels raw/smooth/benchmark data debug.
* 1: 5 channges smooth + benchmark data debug.
* 1: 5 changes smooth + benchmark data debug.
* 2: 1 channels filter data.
*/
#define SCOPE_DEBUG_TYPE 2

Wyświetl plik

@ -120,7 +120,7 @@ int test_tp_print_to_scope(float *data, unsigned char channel_num)
return 0;
} else {
#if ROM_UART_DRIVER_ENABLE
esp_rom_output_tx_wait_idle(uart_num); // Default print uart mumber is 0.
esp_rom_output_tx_wait_idle(uart_num); // Default print uart number is 0.
for (int i = 0; i < out_len; i++) {
esp_rom_output_tx_one_char(out_data[i]);
}
@ -154,7 +154,7 @@ int test_tp_print_to_scope(float *data, unsigned char channel_num)
esp_err_t test_tp_scope_debug_init(uint8_t uart_num, int tx_io_num, int rx_io_num, int baud_rate)
{
#if ROM_UART_DRIVER_ENABLE
esp_rom_output_tx_wait_idle(0); // Default print uart mumber is 0.
esp_rom_output_tx_wait_idle(0); // Default print uart number is 0.
if (uart_num != 0) {
esp_rom_output_set_as_console(uart_num);
}

Wyświetl plik

@ -122,7 +122,7 @@ esp_err_t touch_pad_isr_register(intr_handler_t fn, void *arg);
* @note This function will specify the clock cycles of each measurement
* and the clock is sourced from SOC_MOD_CLK_RTC_FAST, its default frequency is SOC_CLK_RC_FAST_FREQ_APPROX
* The touch sensor will record the charge and discharge times during these clock cycles as the final result (raw value)
* @note If clock cyles is too small, it may lead to inaccurate results.
* @note If clock cycles is too small, it may lead to inaccurate results.
*
* @param clock_cycle The clock cycles of each measurement
* measure_time = clock_cycle / SOC_CLK_RC_FAST_FREQ_APPROX, the maximum measure time is 0xffff / SOC_CLK_RC_FAST_FREQ_APPROX
@ -143,7 +143,7 @@ esp_err_t touch_pad_get_measurement_clock_cycles(uint16_t *clock_cycle);
/**
* @brief Set the interval between two measurements
* @note The touch sensor will sleep between two mesurements
* @note The touch sensor will sleep between two measurements
* This function is to set the interval cycle
* And the interval is clocked from SOC_MOD_CLK_RTC_SLOW, its default frequency is SOC_CLK_RC_SLOW_FREQ_APPROX
*

Wyświetl plik

@ -62,7 +62,7 @@ esp_err_t touch_pad_get_charge_discharge_times(uint16_t *charge_discharge_times)
/**
* @brief Set the interval between two measurements
* @note The touch sensor will sleep between two mesurements
* @note The touch sensor will sleep between two measurements
* This function is to set the interval cycle
* And the interval is clocked from SOC_MOD_CLK_RTC_SLOW, its default frequency is SOC_CLK_RC_SLOW_FREQ_APPROX
*

Wyświetl plik

@ -62,7 +62,7 @@ esp_err_t touch_pad_get_charge_discharge_times(uint16_t *charge_discharge_times)
/**
* @brief Set the interval between two measurements
* @note The touch sensor will sleep between two mesurements
* @note The touch sensor will sleep between two measurements
* This function is to set the interval cycle
* And the interval is clocked from SOC_MOD_CLK_RTC_SLOW, its default frequency is SOC_CLK_RC_SLOW_FREQ_APPROX
*

Wyświetl plik

@ -81,7 +81,7 @@ menu "ADC and ADC Calibration"
bool "Enable ADC debug log"
default n
help
Wether to enable the debug log message for ADC driver.
whether to enable the debug log message for ADC driver.
Note that this option only controls the ADC driver log, will not affect other drivers.
note: This cannot be used in the ADC legacy driver.

Wyświetl plik

@ -86,7 +86,7 @@ static IRAM_ATTR bool adc_dma_intr(adc_continuous_ctx_t *adc_digi_ctx)
uint8_t *old_data = xRingbufferReceiveUpToFromISR(adc_digi_ctx->ringbuf_hdl, &actual_size, adc_digi_ctx->ringbuf_size);
/**
* Replace by ringbuffer reset API when this API is ready.
* Now we do mannual reset.
* Now we do manual reset.
* For old_data == NULL condition (equals to the future ringbuffer reset fail condition), we don't care this time data,
* as this only happens when the ringbuffer size is small, new data will be filled in soon.
*/

Wyświetl plik

@ -191,7 +191,7 @@ esp_err_t adc_continuous_monitor_register_event_callbacks(adc_monitor_handle_t m
{
ESP_RETURN_ON_FALSE(monitor_handle && cbs, ESP_ERR_INVALID_ARG, MNTOR_TAG, "invalid argument: null pointer");
ESP_RETURN_ON_FALSE(monitor_handle->fsm == ADC_MONITOR_FSM_INIT, ESP_ERR_INVALID_STATE, MNTOR_TAG, "monitor should be in init state");
ESP_RETURN_ON_FALSE(!(monitor_handle->cbs.on_over_high_thresh || monitor_handle->cbs.on_below_low_thresh), ESP_ERR_INVALID_STATE, MNTOR_TAG, "callbacks had beed registered");
ESP_RETURN_ON_FALSE(!(monitor_handle->cbs.on_over_high_thresh || monitor_handle->cbs.on_below_low_thresh), ESP_ERR_INVALID_STATE, MNTOR_TAG, "callbacks had been registered");
#if CONFIG_IDF_TARGET_ESP32S2
ESP_RETURN_ON_FALSE(!(cbs->on_below_low_thresh && cbs->on_over_high_thresh), ESP_ERR_NOT_SUPPORTED, MNTOR_TAG, "ESP32S2 support only one threshold");
#endif

Wyświetl plik

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2019-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2019-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -34,10 +34,10 @@ static const int coeff_a_scaling = 65536;
* For each item, first element is the Coefficient, second element is the Multiple. (Coefficient / Multiple) is the real coefficient.
*
* @note {0,0} stands for unused item
* @note In case of the overflow, these coeffcients are recorded as Absolute Value
* @note In case of the overflow, these coefficients are recorded as Absolute Value
* @note For atten0 ~ 2, error = (K0 * X^0) + (K1 * X^1) + (K2 * X^2); For atten3, error = (K0 * X^0) + (K1 * X^1) + (K2 * X^2) + (K3 * X^3) + (K4 * X^4);
* @note Above formula is rewritten from the original documentation, please note that the coefficients are re-ordered.
* @note ADC1 and ADC2 use same coeffients
* @note ADC1 and ADC2 use same coefficients
*/
const static uint64_t adc_error_coef_atten[4][5][2] = {
{{225966470500043, 1e15}, {7265418501948, 1e16}, {109410402681, 1e16}, {0, 0}, {0, 0}}, //atten0
@ -47,7 +47,7 @@ const static uint64_t adc_error_coef_atten[4][5][2] = {
};
/**
* Term sign
* @note ADC1 and ADC2 use same coeffients
* @note ADC1 and ADC2 use same coefficients
*/
const static int32_t adc_error_sign[4][5] = {
{-1, -1, 1, 0, 0}, //atten0
@ -130,7 +130,7 @@ esp_adc_cal_value_t esp_adc_cal_characterize(adc_unit_t adc_num,
adc_calib_parsed_info_t efuse_parsed_data = {0};
// Check parameters
ESP_RETURN_ON_FALSE(adc_num == ADC_UNIT_1 || adc_num == ADC_UNIT_2, ESP_ADC_CAL_VAL_NOT_SUPPORTED, LOG_TAG, "Invalid unit num");
ESP_RETURN_ON_FALSE(chars != NULL, ESP_ADC_CAL_VAL_NOT_SUPPORTED, LOG_TAG, "Ivalid characteristic");
ESP_RETURN_ON_FALSE(chars != NULL, ESP_ADC_CAL_VAL_NOT_SUPPORTED, LOG_TAG, "Invalid characteristic");
ESP_RETURN_ON_FALSE(bit_width == ADC_WIDTH_BIT_12, ESP_ADC_CAL_VAL_NOT_SUPPORTED, LOG_TAG, "Invalid bit_width");
ESP_RETURN_ON_FALSE(atten < SOC_ADC_ATTEN_NUM, ESP_ADC_CAL_VAL_NOT_SUPPORTED, LOG_TAG, "Invalid attenuation");

Wyświetl plik

@ -34,7 +34,7 @@ static const int coeff_a_scaling = 1000000;
* For each item, first element is the Coefficient, second element is the Multiple. (Coefficient / Multiple) is the real coefficient.
*
* @note {0,0} stands for unused item
* @note In case of the overflow, these coeffcients are recorded as Absolute Value
* @note In case of the overflow, these coefficients are recorded as Absolute Value
* @note For atten0 ~ 2, error = (K0 * X^0) + (K1 * X^1) + (K2 * X^2); For atten3, error = (K0 * X^0) + (K1 * X^1) + (K2 * X^2) + (K3 * X^3) + (K4 * X^4);
* @note Above formula is rewritten from the original documentation, please note that the coefficients are re-ordered.
*/
@ -133,7 +133,7 @@ esp_adc_cal_value_t esp_adc_cal_characterize(adc_unit_t adc_num,
// Check parameters
ESP_RETURN_ON_FALSE(adc_num == ADC_UNIT_1 || adc_num == ADC_UNIT_2, ESP_ADC_CAL_VAL_NOT_SUPPORTED, LOG_TAG, "Invalid unit num");
ESP_RETURN_ON_FALSE(chars != NULL, ESP_ADC_CAL_VAL_NOT_SUPPORTED, LOG_TAG, "Ivalid characteristic");
ESP_RETURN_ON_FALSE(chars != NULL, ESP_ADC_CAL_VAL_NOT_SUPPORTED, LOG_TAG, "Invalid characteristic");
ESP_RETURN_ON_FALSE(atten < SOC_ADC_ATTEN_NUM, ESP_ADC_CAL_VAL_NOT_SUPPORTED, LOG_TAG, "Invalid attenuation");
int version_num = esp_efuse_rtc_calib_get_ver();

Wyświetl plik

@ -25,7 +25,7 @@
* 1. Rename this file to `adc_cali_line_fitting_v2.c`, as the Line Fitting Scheme on ESP32 and ESP32S2 are different to this.
* 2. Move this file to common directory
* 3. Still support `ADC_CALI_SCHEME_LINE_FITTING_SUPPORTED`
* 4. Add a new internal maccro `ADC_CALI_SCHEME_LINE_FITTING_V2_SUPPORTED`
* 4. Add a new internal macro `ADC_CALI_SCHEME_LINE_FITTING_V2_SUPPORTED`
* 5. Only build this file, when `ADC_CALI_SCHEME_LINE_FITTING_V2_SUPPORTED == true`
*/

Wyświetl plik

@ -103,7 +103,7 @@ typedef struct {
/**
* @brief Initialize ADC continuous driver and get a handle to it
*
* @param[in] hdl_config Pointer to ADC initilization config. Refer to ``adc_continuous_handle_cfg_t``.
* @param[in] hdl_config Pointer to ADC initialization config. Refer to ``adc_continuous_handle_cfg_t``.
* @param[out] ret_handle ADC continuous mode driver handle
*
* @return

Wyświetl plik

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2022-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2022-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -303,9 +303,9 @@ TEST_CASE("test ADC2 Single Read with Light Sleep", "[adc]")
#if SOC_ADC_MONITOR_SUPPORTED && CONFIG_SOC_ADC_DMA_SUPPORTED
#if CONFIG_IDF_TARGET_ESP32S2
#define TEST_ADC_FORMATE_TYPE ADC_DIGI_OUTPUT_FORMAT_TYPE1
#define TEST_ADC_FORMAT_TYPE ADC_DIGI_OUTPUT_FORMAT_TYPE1
#else
#define TEST_ADC_FORMATE_TYPE ADC_DIGI_OUTPUT_FORMAT_TYPE2
#define TEST_ADC_FORMAT_TYPE ADC_DIGI_OUTPUT_FORMAT_TYPE2
#endif
bool IRAM_ATTR test_high_cb(adc_monitor_handle_t monitor_handle, const adc_monitor_evt_data_t *event_data, void *user_data)
{
@ -332,7 +332,7 @@ TEST_CASE("ADC continuous monitor init_deinit", "[adc]")
.adc_pattern = adc_pattern,
.sample_freq_hz = SOC_ADC_SAMPLE_FREQ_THRES_LOW,
.conv_mode = ADC_CONV_SINGLE_UNIT_1,
.format = TEST_ADC_FORMATE_TYPE,
.format = TEST_ADC_FORMAT_TYPE,
};
TEST_ESP_OK(adc_continuous_config(handle, &dig_cfg));
@ -450,7 +450,7 @@ TEST_CASE("ADC continuous monitor functionary", "[adc][manual][ignore]")
.adc_pattern = adc_pattern,
.sample_freq_hz = SOC_ADC_SAMPLE_FREQ_THRES_LOW,
.conv_mode = ADC_CONV_SINGLE_UNIT_1,
.format = TEST_ADC_FORMATE_TYPE,
.format = TEST_ADC_FORMAT_TYPE,
};
TEST_ESP_OK(adc_continuous_config(handle, &dig_cfg));

Wyświetl plik

@ -47,7 +47,7 @@ static bool IRAM_ATTR s_alarm_callback(gptimer_handle_t timer, const gptimer_ala
/**
* This test won't disable the cache, so having some code on Flash is OK.
* If you copy this test callback with cache disabled, do remeber to put all code in internal RAM.
* If you copy this test callback with cache disabled, do remember to put all code in internal RAM.
*/
esp_rom_printf("alarm isr count=%llu\r\n", edata->count_value);
@ -213,7 +213,7 @@ TEST_CASE("ADC continuous big conv_frame_size test", "[adc_continuous]")
#define ADC_FLUSH_TEST_SIZE 64
TEST_CASE("ADC continuous flush internal pool", "[adc_continuous][mannual][ignore]")
TEST_CASE("ADC continuous flush internal pool", "[adc_continuous][manual][ignore]")
{
adc_continuous_handle_t handle = NULL;
adc_continuous_handle_cfg_t adc_config = {

Wyświetl plik

@ -19,6 +19,6 @@ menu "ESP-Driver:Analog Comparator Configurations"
bool "Enable debug log"
default n
help
Wether to enable the debug log message for Analog Comparator driver.
whether to enable the debug log message for Analog Comparator driver.
Note that, this option only controls the Analog Comparator driver log, won't affect other drivers.
endmenu # Analog Comparator Configuration

Wyświetl plik

@ -31,7 +31,7 @@ typedef struct {
int intr_priority; /*!< The interrupt priority, range 0~7, if set to 0, the driver will try to allocate an interrupt with a relative low priority (1,2,3)
* otherwise the larger the higher, 7 is NMI */
struct {
uint32_t io_loop_back: 1; /*!< Enable this field when the other signals that output on the comparision pins are supposed to be fed back.
uint32_t io_loop_back: 1; /*!< Enable this field when the other signals that output on the comparison pins are supposed to be fed back.
* Normally used for debug/test scenario */
} flags; /*!< Analog comparator driver flags */
} ana_cmpr_config_t;

Wyświetl plik

@ -33,7 +33,7 @@ typedef struct {
mipi_csi_color_t input_data_color_type; ///< Input color type
mipi_csi_color_t output_data_color_type; ///< Output color type
bool byte_swap_en; ///< Enable byte swap
int queue_items; ///< Queue itmes
int queue_items; ///< Queue items
} esp_cam_ctlr_csi_config_t;
/**

Wyświetl plik

@ -186,7 +186,7 @@ esp_err_t esp_cam_new_csi_ctlr(const esp_cam_ctlr_csi_config_t *config, esp_cam_
.flow_controller = DW_GDMA_FLOW_CTRL_SRC,
.chan_priority = 1,
};
ESP_GOTO_ON_ERROR(dw_gdma_new_channel(&csi_dma_alloc_config, &csi_dma_chan), err, TAG, "failed to new dwgdma channle");
ESP_GOTO_ON_ERROR(dw_gdma_new_channel(&csi_dma_alloc_config, &csi_dma_chan), err, TAG, "failed to new dwgdma channel");
ctlr->dma_chan = csi_dma_chan;
size_t csi_transfer_size = ctlr->h_res * ctlr->v_res * ctlr->in_bpp / 64;

Wyświetl plik

@ -19,7 +19,7 @@ menu "ESP-Driver:DAC Configurations"
bool "Suppress legacy driver deprecated warning"
default n
help
Wether to suppress the deprecation warnings when using legacy DAC driver (driver/dac.h).
whether to suppress the deprecation warnings when using legacy DAC driver (driver/dac.h).
If you want to continue using the legacy driver, and don't want to see related deprecation warnings,
you can enable this option.
@ -27,7 +27,7 @@ menu "ESP-Driver:DAC Configurations"
bool "Enable debug log"
default n
help
Wether to enable the debug log message for DAC driver.
whether to enable the debug log message for DAC driver.
Note that, this option only controls the DAC driver log, won't affect other drivers.
config DAC_DMA_AUTO_16BIT_ALIGN

Wyświetl plik

@ -38,7 +38,7 @@ typedef enum {
} dac_continuous_channel_mode_t;
/**
* @brief DAC DMA (digitial controller) clock source
* @brief DAC DMA (digital controller) clock source
*
*/
typedef soc_periph_dac_digi_clk_src_t dac_continuous_digi_clk_src_t;

Wyświetl plik

@ -231,7 +231,7 @@ TEST_CASE("DAC_dma_write_test", "[dac]")
* The frequency test is currently only supported on ESP32
* because there is no such signal to monitor on ESP32-S2 */
#if CONFIG_IDF_TARGET_ESP32
TEST_CASE("DAC_dma_conver_frequency_test", "[dac]")
TEST_CASE("DAC_dma_convert_frequency_test", "[dac]")
{
/* Prepare configuration for the PCNT unit */
pcnt_unit_handle_t pcnt_unit = NULL;

Wyświetl plik

@ -399,7 +399,7 @@ esp_err_t gpio_hold_en(gpio_num_t gpio_num);
* e.g.
* If you hold gpio18 high during Deep-sleep, after the chip is woken up and `gpio_hold_dis` is called,
* gpio18 will output low level(because gpio18 is input mode by default). If you don't want this behavior,
* you should configure gpio18 as output mode and set it to hight level before calling `gpio_hold_dis`.
* you should configure gpio18 as output mode and set it to high level before calling `gpio_hold_dis`.
*
* @param gpio_num GPIO number, only support output-capable GPIOs
*
@ -442,9 +442,9 @@ void gpio_iomux_in(uint32_t gpio_num, uint32_t signal_idx);
* @param gpio_num gpio_num GPIO number of the pad.
* @param func The function number of the peripheral pin to output pin.
* One of the ``FUNC_X_*`` of specified pin (X) in ``soc/io_mux_reg.h``.
* @param oen_inv True if the output enable needs to be inverted, otherwise False.
* @param out_en_inv True if the output enable needs to be inverted, otherwise False.
*/
void gpio_iomux_out(uint8_t gpio_num, int func, bool oen_inv);
void gpio_iomux_out(uint8_t gpio_num, int func, bool out_en_inv);
#if SOC_GPIO_SUPPORT_FORCE_HOLD
/**

Wyświetl plik

@ -38,12 +38,12 @@ esp_err_t lp_gpio_connect_in_signal(gpio_num_t gpio_num, uint32_t signal_idx, bo
* @param gpio_num GPIO number
* @param signal_idx LP peripheral signal index (tagged as input attribute), especially, `SIG_LP_GPIO_OUT_IDX` means disconnect RTC(LP) GPIO and other peripherals. Only the RTC GPIO driver can control the output level
* @param out_inv Whether to signal to be inverted or not
* @param oen_inv Whether the output enable control is inverted or not
* @param out_en_inv Whether the output enable control is inverted or not
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t lp_gpio_connect_out_signal(gpio_num_t gpio_num, uint32_t signal_idx, bool out_inv, bool oen_inv);
esp_err_t lp_gpio_connect_out_signal(gpio_num_t gpio_num, uint32_t signal_idx, bool out_inv, bool out_en_inv);
#endif // SOC_LP_GPIO_MATRIX_SUPPORTED
#ifdef __cplusplus

Wyświetl plik

@ -75,7 +75,7 @@ static esp_err_t dedic_gpio_build_platform(int core_id)
if (!s_platform[core_id]) {
s_platform[core_id] = calloc(1, sizeof(dedic_gpio_platform_t));
if (s_platform[core_id]) {
// initialize platfrom members
// initialize platform members
s_platform[core_id]->spinlock = (portMUX_TYPE)portMUX_INITIALIZER_UNLOCKED;
// initial occupy_mask: 1111...100...0
s_platform[core_id]->out_occupied_mask = UINT32_MAX & ~((1 << SOC_DEDIC_GPIO_OUT_CHANNELS_NUM) - 1);

Wyświetl plik

@ -98,7 +98,7 @@ esp_err_t gpio_pullup_en(gpio_num_t gpio_num)
#if SOC_RTCIO_INPUT_OUTPUT_SUPPORTED
rtc_gpio_pullup_en(gpio_num);
#else
abort(); // This should be eliminated as unreachable, unless a programming error has occured
abort(); // This should be eliminated as unreachable, unless a programming error has occurred
#endif
}
@ -117,7 +117,7 @@ esp_err_t gpio_pullup_dis(gpio_num_t gpio_num)
#if SOC_RTCIO_INPUT_OUTPUT_SUPPORTED
rtc_gpio_pullup_dis(gpio_num);
#else
abort(); // This should be eliminated as unreachable, unless a programming error has occured
abort(); // This should be eliminated as unreachable, unless a programming error has occurred
#endif
}
@ -136,7 +136,7 @@ esp_err_t gpio_pulldown_en(gpio_num_t gpio_num)
#if SOC_RTCIO_INPUT_OUTPUT_SUPPORTED
rtc_gpio_pulldown_en(gpio_num);
#else
abort(); // This should be eliminated as unreachable, unless a programming error has occured
abort(); // This should be eliminated as unreachable, unless a programming error has occurred
#endif
}
@ -155,7 +155,7 @@ esp_err_t gpio_pulldown_dis(gpio_num_t gpio_num)
#if SOC_RTCIO_INPUT_OUTPUT_SUPPORTED
rtc_gpio_pulldown_dis(gpio_num);
#else
abort(); // This should be eliminated as unreachable, unless a programming error has occured
abort(); // This should be eliminated as unreachable, unless a programming error has occurred
#endif
}
@ -689,7 +689,7 @@ esp_err_t gpio_set_drive_capability(gpio_num_t gpio_num, gpio_drive_cap_t streng
#if SOC_RTCIO_INPUT_OUTPUT_SUPPORTED
ret = rtc_gpio_set_drive_capability(gpio_num, strength);
#else
abort(); // This should be eliminated as unreachable, unless a programming error has occured
abort(); // This should be eliminated as unreachable, unless a programming error has occurred
#endif
}
@ -710,7 +710,7 @@ esp_err_t gpio_get_drive_capability(gpio_num_t gpio_num, gpio_drive_cap_t *stren
#if SOC_RTCIO_INPUT_OUTPUT_SUPPORTED
ret = rtc_gpio_get_drive_capability(gpio_num, strength);
#else
abort(); // This should be eliminated as unreachable, unless a programming error has occured
abort(); // This should be eliminated as unreachable, unless a programming error has occurred
#endif
}
@ -802,9 +802,9 @@ void gpio_iomux_in(uint32_t gpio, uint32_t signal_idx)
gpio_hal_iomux_in(gpio_context.gpio_hal, gpio, signal_idx);
}
void gpio_iomux_out(uint8_t gpio_num, int func, bool oen_inv)
void gpio_iomux_out(uint8_t gpio_num, int func, bool out_en_inv)
{
gpio_hal_iomux_out(gpio_context.gpio_hal, gpio_num, func, (uint32_t)oen_inv);
gpio_hal_iomux_out(gpio_context.gpio_hal, gpio_num, func, (uint32_t)out_en_inv);
}
static esp_err_t gpio_sleep_pullup_en(gpio_num_t gpio_num)

Wyświetl plik

@ -194,10 +194,10 @@ esp_err_t lp_gpio_connect_in_signal(gpio_num_t gpio_num, uint32_t signal_idx, bo
return ESP_OK;
}
esp_err_t lp_gpio_connect_out_signal(gpio_num_t gpio_num, uint32_t signal_idx, bool out_inv, bool oen_inv)
esp_err_t lp_gpio_connect_out_signal(gpio_num_t gpio_num, uint32_t signal_idx, bool out_inv, bool out_en_inv)
{
ESP_RETURN_ON_FALSE(rtc_gpio_is_valid_gpio(gpio_num), ESP_ERR_INVALID_ARG, RTCIO_TAG, "LP_IO number error");
rtcio_hal_matrix_out(rtc_io_number_get(gpio_num), signal_idx, out_inv, oen_inv);
rtcio_hal_matrix_out(rtc_io_number_get(gpio_num), signal_idx, out_inv, out_en_inv);
return ESP_OK;
}
#endif // SOC_LP_GPIO_MATRIX_SUPPORTED

Wyświetl plik

@ -11,7 +11,7 @@
/**
* NOTE: To run this special feature test case, a slope analog signal is needed.
* A simple RC circuit used here to formate pin switches to continuos slop signal.
* A simple RC circuit used here to generate continuous slope signal.
*
* +---------+
* | |

Wyświetl plik

@ -26,6 +26,6 @@ menu "ESP-Driver:GPTimer Configurations"
bool "Enable debug log"
default n
help
Wether to enable the debug log message for GPTimer driver.
whether to enable the debug log message for GPTimer driver.
Note that, this option only controls the GPTimer driver log, won't affect other drivers.
endmenu

Wyświetl plik

@ -12,7 +12,7 @@ menu "ESP-Driver:I2C Configurations"
bool "Enable I2C debug log"
default n
help
Wether to enable the debug log message for I2C driver.
whether to enable the debug log message for I2C driver.
Note that this option only controls the I2C driver log, will not affect other drivers.
note: This cannot be used in the I2C legacy driver.

Wyświetl plik

@ -41,7 +41,7 @@ typedef struct i2c_platform_t {
static i2c_platform_t s_i2c_platform = {}; // singleton platform
static esp_err_t s_i2c_bus_handle_aquire(i2c_port_num_t port_num, i2c_bus_handle_t *i2c_new_bus, i2c_bus_mode_t mode)
static esp_err_t s_i2c_bus_handle_acquire(i2c_port_num_t port_num, i2c_bus_handle_t *i2c_new_bus, i2c_bus_mode_t mode)
{
#if CONFIG_I2C_ENABLE_DEBUG_LOG
esp_log_level_set(TAG, ESP_LOG_DEBUG);
@ -104,7 +104,7 @@ esp_err_t i2c_acquire_bus_handle(i2c_port_num_t port_num, i2c_bus_handle_t *i2c_
for (int i = 0; i < SOC_I2C_NUM; i++) {
bus_occupied = i2c_bus_occupied(i);
if (bus_occupied == false) {
ret = s_i2c_bus_handle_aquire(i, i2c_new_bus, mode);
ret = s_i2c_bus_handle_acquire(i, i2c_new_bus, mode);
if (ret != ESP_OK) {
ESP_LOGE(TAG, "acquire bus failed");
_lock_release(&s_i2c_platform.mutex);
@ -117,7 +117,7 @@ esp_err_t i2c_acquire_bus_handle(i2c_port_num_t port_num, i2c_bus_handle_t *i2c_
}
ESP_RETURN_ON_FALSE((bus_found == true), ESP_ERR_NOT_FOUND, TAG, "acquire bus failed, no free bus");
} else {
ret = s_i2c_bus_handle_aquire(port_num, i2c_new_bus, mode);
ret = s_i2c_bus_handle_acquire(port_num, i2c_new_bus, mode);
if (ret != ESP_OK) {
ESP_LOGE(TAG, "acquire bus failed");
}

Wyświetl plik

@ -119,7 +119,7 @@ static esp_err_t s_i2c_hw_fsm_reset(i2c_master_bus_handle_t i2c_master)
*
* @param[in] i2c_master I2C master handle
* @param[in] i2c_operation Pointer to I2C trans operation structure.
* @param[in] fifo_fill will be populated with the number of bytes written to the harware FIFO by this function
* @param[in] fifo_fill will be populated with the number of bytes written to the hardware FIFO by this function
* @param[in] address_fill I2C device address with read or write information.
*/
static bool s_i2c_write_command(i2c_master_bus_handle_t i2c_master, i2c_operation_t *i2c_operation, uint8_t *fifo_fill, uint8_t *address_fill, BaseType_t *do_yield)

Wyświetl plik

@ -108,7 +108,7 @@ struct i2c_bus_t {
int scl_num; // SCL pin number
bool pull_up_enable; // Enable pull-ups
intr_handle_t intr_handle; // I2C interrupt handle
esp_pm_lock_handle_t pm_lock; // power manange lock
esp_pm_lock_handle_t pm_lock; // power manage lock
#if CONFIG_PM_ENABLE
char pm_lock_name[I2C_PM_LOCK_NAME_LEN_MAX]; // pm lock name
#endif
@ -141,7 +141,7 @@ struct i2c_master_bus_t {
bool ack_check_disable; // Disable ACK check
volatile bool trans_done; // transaction command finish
SLIST_HEAD(i2c_master_device_list_head, i2c_master_device_list) device_list; // I2C device (instance) list
// asnyc trans members
// async trans members
bool async_break; // break transaction loop flag.
i2c_addr_bit_len_t addr_10bits_bus; // Slave address is 10 bits.
size_t queue_size; // I2C transaction queue size.

Wyświetl plik

@ -320,7 +320,7 @@ esp_err_t i2c_slave_transmit(i2c_slave_dev_handle_t i2c_slave, const uint8_t *da
{
ESP_RETURN_ON_FALSE(i2c_slave, ESP_ERR_INVALID_ARG, TAG, "i2c slave not initialized");
ESP_RETURN_ON_FALSE(data, ESP_ERR_INVALID_ARG, TAG, "invalid data buffer");
ESP_RETURN_ON_FALSE((i2c_slave->fifo_mode == I2C_SLAVE_FIFO), ESP_ERR_NOT_SUPPORTED, TAG, "non-fifo mode is not suppored in this API, please set access_ram_en to false");
ESP_RETURN_ON_FALSE((i2c_slave->fifo_mode == I2C_SLAVE_FIFO), ESP_ERR_NOT_SUPPORTED, TAG, "non-fifo mode is not supported in this API, please set access_ram_en to false");
esp_err_t ret = ESP_OK;
i2c_hal_context_t *hal = &i2c_slave->base->hal;
TickType_t wait_ticks = (xfer_timeout_ms == -1) ? portMAX_DELAY : pdMS_TO_TICKS(xfer_timeout_ms);
@ -340,7 +340,7 @@ esp_err_t i2c_slave_receive(i2c_slave_dev_handle_t i2c_slave, uint8_t *data, siz
{
ESP_RETURN_ON_FALSE(i2c_slave, ESP_ERR_INVALID_ARG, TAG, "i2c slave not initialized");
ESP_RETURN_ON_FALSE(data, ESP_ERR_INVALID_ARG, TAG, "invalid data buffer");
ESP_RETURN_ON_FALSE((i2c_slave->fifo_mode == I2C_SLAVE_FIFO), ESP_ERR_NOT_SUPPORTED, TAG, "non-fifo mode is not suppored in this API, please set access_ram_en to false");
ESP_RETURN_ON_FALSE((i2c_slave->fifo_mode == I2C_SLAVE_FIFO), ESP_ERR_NOT_SUPPORTED, TAG, "non-fifo mode is not supported in this API, please set access_ram_en to false");
#if CONFIG_I2C_ISR_IRAM_SAFE
ESP_RETURN_ON_FALSE(esp_ptr_internal(data), ESP_ERR_INVALID_ARG, TAG, "buffer must locate in internal RAM if IRAM_SAFE is enabled");
#endif
@ -365,7 +365,7 @@ esp_err_t i2c_slave_read_ram(i2c_slave_dev_handle_t i2c_slave, uint8_t ram_offse
ESP_RETURN_ON_FALSE(i2c_slave, ESP_ERR_INVALID_ARG, TAG, "i2c slave not initialized");
ESP_RETURN_ON_FALSE(data, ESP_ERR_INVALID_ARG, TAG, "invalid data buffer");
ESP_RETURN_ON_FALSE((ram_offset + receive_size <= SOC_I2C_FIFO_LEN), ESP_ERR_INVALID_SIZE, TAG, "don't read data cross fifo boundary, see `SOC_I2C_FIFO_LEN`");
ESP_RETURN_ON_FALSE((i2c_slave->fifo_mode == I2C_SLAVE_NONFIFO), ESP_ERR_NOT_SUPPORTED, TAG, "fifo mode is not suppored in this API, please set access_ram_en to true");
ESP_RETURN_ON_FALSE((i2c_slave->fifo_mode == I2C_SLAVE_NONFIFO), ESP_ERR_NOT_SUPPORTED, TAG, "fifo mode is not supported in this API, please set access_ram_en to true");
i2c_hal_context_t *hal = &i2c_slave->base->hal;
uint32_t fifo_size = 0;
@ -386,7 +386,7 @@ esp_err_t i2c_slave_write_ram(i2c_slave_dev_handle_t i2c_slave, uint8_t ram_offs
{
ESP_RETURN_ON_FALSE(i2c_slave, ESP_ERR_INVALID_ARG, TAG, "i2c slave not initialized");
ESP_RETURN_ON_FALSE(data, ESP_ERR_INVALID_ARG, TAG, "invalid data buffer");
ESP_RETURN_ON_FALSE((i2c_slave->fifo_mode == I2C_SLAVE_NONFIFO), ESP_ERR_NOT_SUPPORTED, TAG, "fifo mode is not suppored in this API, please set access_ram_en to true");
ESP_RETURN_ON_FALSE((i2c_slave->fifo_mode == I2C_SLAVE_NONFIFO), ESP_ERR_NOT_SUPPORTED, TAG, "fifo mode is not supported in this API, please set access_ram_en to true");
i2c_hal_context_t *hal = &i2c_slave->base->hal;
ESP_RETURN_ON_FALSE(xSemaphoreTake(i2c_slave->slv_tx_mux, portMAX_DELAY) == pdTRUE, ESP_ERR_TIMEOUT, TAG, "write to ram lock timeout");

Wyświetl plik

@ -40,7 +40,7 @@ typedef struct {
uint32_t scl_speed_hz; /*!< I2C SCL line frequency. */
uint32_t scl_wait_us; /*!< Timeout value. (unit: us). Please note this value should not be so small that it can handle stretch/disturbance properly. If 0 is set, that means use the default reg value*/
struct {
uint32_t disable_ack_check: 1; /*!< Disable ACK check. If this is set false, that means ack check is enabled, the transaction will be stoped and API returns error when nack is detected. */
uint32_t disable_ack_check: 1; /*!< Disable ACK check. If this is set false, that means ack check is enabled, the transaction will be stopped and API returns error when nack is detected. */
} flags; /*!< I2C device config flags */
} i2c_device_config_t;

Wyświetl plik

@ -181,7 +181,7 @@ static IRAM_ATTR bool test_master_tx_done_callback(i2c_master_dev_handle_t i2c_d
*
* 1. See the depth of queue is 37, but the number of transaction is 42, that means some
* queue must be reused.
* 2. There are some delay randomly set there, for testing the concurency or any I2C state
* 2. There are some delay randomly set there, for testing the concurrency or any I2C state
* might be met.
*******************************************************************************
*/

Wyświetl plik

@ -614,7 +614,7 @@ static void slave_init_for_probe(void)
TEST_CASE_MULTIPLE_DEVICES("I2C master probe slave test", "[i2c][test_env=generic_multi_device][timeout=150]", master_probe_slave, slave_init_for_probe);
#if SOC_I2C_NUM > 1
// Now chips with mutiple I2C controllers are up to 2, can change this to interation when we have more I2C controllers.
// Now chips with multiple I2C controllers are up to 2, can test more ports when we have more I2C controllers.
static void i2c_master_write_test_more_port(void)
{
uint8_t data_wr[DATA_LENGTH] = { 0 };

Wyświetl plik

@ -17,6 +17,6 @@ menu "ESP-Driver:I2S Configurations"
bool "Enable I2S debug log"
default n
help
Wether to enable the debug log message for I2S driver.
whether to enable the debug log message for I2S driver.
Note that, this option only controls the I2S driver log, will not affect other drivers.
endmenu # I2S Configuration

Wyświetl plik

@ -366,7 +366,7 @@ uint32_t i2s_get_buf_size(i2s_chan_handle_t handle, uint32_t data_bit_width, uin
}
}
if (bufsize / bytes_per_frame != dma_frame_num) {
ESP_LOGW(TAG, "dma frame num is adjusted to %"PRIu32" to algin the dma buffer with %"PRIu32
ESP_LOGW(TAG, "dma frame num is adjusted to %"PRIu32" to align the dma buffer with %"PRIu32
", bufsize = %"PRIu32, bufsize / bytes_per_frame, alignment, bufsize);
}
#endif
@ -417,7 +417,7 @@ esp_err_t i2s_alloc_dma_desc(i2s_chan_handle_t handle, uint32_t num, uint32_t bu
/* Descriptors must be in the internal RAM */
handle->dma.desc = (lldesc_t **)heap_caps_calloc(num, sizeof(lldesc_t *), I2S_MEM_ALLOC_CAPS);
ESP_GOTO_ON_FALSE(handle->dma.desc, ESP_ERR_NO_MEM, err, TAG, "create I2S DMA decriptor array failed");
ESP_GOTO_ON_FALSE(handle->dma.desc, ESP_ERR_NO_MEM, err, TAG, "create I2S DMA descriptor array failed");
handle->dma.bufs = (uint8_t **)heap_caps_calloc(num, sizeof(uint8_t *), I2S_MEM_ALLOC_CAPS);
size_t desc_size = 0;
for (int i = 0; i < num; i++) {

Wyświetl plik

@ -134,7 +134,7 @@ struct i2s_channel_obj_t {
int intr_prio_flags;/*!< i2s interrupt priority flags */
void *mode_info; /*!< Slot, clock and gpio information of each mode */
#if SOC_I2S_SUPPORTS_APLL
bool apll_en; /*!< Flag of wether APLL enabled */
bool apll_en; /*!< Flag of whether APLL enabled */
#endif
uint32_t active_slot; /*!< Active slot number */
uint32_t total_slot; /*!< Total slot number */

Wyświetl plik

@ -349,7 +349,7 @@ TEST_CASE("I2S_thread_concurrent_safety_test", "[i2s]")
xTaskCreate(i2s_read_task, "i2s_read_task", 4096, rx_handle, 5, NULL);
/* writing task to keep writing */
xTaskCreate(i2s_write_task, "i2s_write_task", 4096, tx_handle, 5, NULL);
/* reconfig taks to reconfigurate the settings every 200 ms */
/* reconfig task to reconfigure the settings every 200 ms */
xTaskCreate(i2s_reconfig_task, "i2s_reconfig_task", 4096, tx_handle, 6, NULL);
/* Wait 3 seconds to see if any failures occur */

Wyświetl plik

@ -5,7 +5,7 @@ menu "ESP-Driver:JPEG-Codec Configurations"
bool "Enable debug log"
default n
help
Wether to enable the debug log message for JPEG driver.
whether to enable the debug log message for JPEG driver.
Note that, this option only controls the JPEG driver log, won't affect other drivers.
Please also note, enable this option will make jpeg codec process speed much slower.

Wyświetl plik

@ -32,7 +32,7 @@ typedef struct {
} jpeg_decode_engine_cfg_t;
/**
* @brief Stucture for jpeg decode header
* @brief Structure for jpeg decode header
*/
typedef struct {
uint32_t width; /*!< Number of pixels in the horizontal direction */

Wyświetl plik

@ -95,7 +95,7 @@ esp_err_t jpeg_new_decoder_engine(const jpeg_decode_engine_cfg_t *dec_eng_cfg, j
/// init jpeg interrupt.
jpeg_ll_clear_intr_mask(hal->dev, JPEG_LL_DECODER_EVENT_INTR);
ESP_GOTO_ON_ERROR(jpeg_check_intr_priority(decoder_engine->codec_base, dec_eng_cfg->intr_priority), err, TAG, "set group intrrupt priority failed");
ESP_GOTO_ON_ERROR(jpeg_check_intr_priority(decoder_engine->codec_base, dec_eng_cfg->intr_priority), err, TAG, "set group interrupt priority failed");
if (dec_eng_cfg->intr_priority) {
ESP_RETURN_ON_FALSE(1 << (dec_eng_cfg->intr_priority) & JPEG_ALLOW_INTR_PRIORITY_MASK, ESP_ERR_INVALID_ARG, TAG, "invalid interrupt priority:%d", dec_eng_cfg->intr_priority);
}
@ -159,7 +159,7 @@ esp_err_t jpeg_decoder_get_info(const uint8_t *in_buf, uint32_t inbuf_len, jpeg_
width = jpeg_get_bytes(header_info, 2);
break;
}
// This function only used for get width and hight. So only read SOF marker is enough.
// This function only used for get width and height. So only read SOF marker is enough.
// Can be extended if picture information is extended.
if (marker == JPEG_M_SOF0) {
break;
@ -201,7 +201,7 @@ esp_err_t jpeg_decoder_process(jpeg_decoder_handle_t decoder_engine, const jpeg_
ESP_GOTO_ON_ERROR(jpeg_dec_config_dma_descriptor(decoder_engine), err, TAG, "config dma descriptor failed");
*out_size = decoder_engine->header_info->process_h * decoder_engine->header_info->process_v * decoder_engine->pixel;
ESP_GOTO_ON_FALSE((*out_size <= outbuf_size), ESP_ERR_INVALID_ARG, err, TAG, "Given buffer size % " PRId32 " is smaller than actual jpeg decode output size % " PRId32 "the hight and width of output picture size will be adjusted to 16 bytes aligned automatically", outbuf_size, *out_size);
ESP_GOTO_ON_FALSE((*out_size <= outbuf_size), ESP_ERR_INVALID_ARG, err, TAG, "Given buffer size % " PRId32 " is smaller than actual jpeg decode output size % " PRId32 "the height and width of output picture size will be adjusted to 16 bytes aligned automatically", outbuf_size, *out_size);
dma2d_trans_config_t trans_desc = {
.tx_channel_num = 1,
@ -682,7 +682,7 @@ static void s_decoder_error_log_print(uint32_t status)
if (status & JPEG_LL_INTR_MARKER_ERR_OTHER) {
ESP_LOGE(TAG, "there is an error in the non-first SCAN header information parsed by the decoder.");
}
if (status & JPEG_LL_INTR_UNDET) {
if (status & JPEG_LL_INTR_UNDETECT) {
ESP_LOGE(TAG, "the bitstream of a image is completely read from 2D DMA but the SOS marker is not read");
}
if (status & JPEG_LL_INTR_DECODE_TIMEOUT) {

Wyświetl plik

@ -49,7 +49,7 @@ struct jpeg_codec_t {
intr_handle_t intr_handle; // jpeg codec interrupt handler
int intr_priority; // jpeg codec interrupt priority
SLIST_HEAD(jpeg_isr_handler_list_, jpeg_isr_handler_) jpeg_isr_handler_list; // List for jpeg interrupt.
esp_pm_lock_handle_t pm_lock; // power manange lock
esp_pm_lock_handle_t pm_lock; // power manage lock
};
typedef enum {

Wyświetl plik

@ -491,11 +491,11 @@ esp_err_t ledc_fade_start(ledc_mode_t speed_mode, ledc_channel_t channel, ledc_f
#if SOC_LEDC_SUPPORT_FADE_STOP
/**
* @brief Stop LEDC fading. The duty of the channel is garanteed to be fixed at most one PWM cycle after the function returns.
* @brief Stop LEDC fading. The duty of the channel is guaranteed to be fixed at most one PWM cycle after the function returns.
*
* @note This API can be called if a new fixed duty or a new fade want to be set while the last fade operation is still running in progress.
* @note Call this API will abort the fading operation only if it was started by calling ledc_fade_start with LEDC_FADE_NO_WAIT mode.
* @note If a fade was started with LEDC_FADE_WAIT_DONE mode, calling this API afterwards has no use in stopping the fade. Fade will continue until it reachs the target duty.
* @note If a fade was started with LEDC_FADE_WAIT_DONE mode, calling this API afterwards has no use in stopping the fade. Fade will continue until it reaches the target duty.
*
* @param speed_mode Select the LEDC channel group with specified speed mode. Note that not all targets support high speed mode.
* @param channel LEDC channel number

Wyświetl plik

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2015-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2015-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -35,7 +35,7 @@ static __attribute__((unused)) const char *LEDC_TAG = "ledc";
#define LEDC_SLOW_CLK_UNINIT -1
#define LEDC_TIMER_SPECIFIC_CLK_UNINIT -1
// Precision degree only affects RC_FAST, other clock sources' frequences are fixed values
// Precision degree only affects RC_FAST, other clock sources' frequencies are fixed values
// For targets that do not support RC_FAST calibration, can only use its approx. value. Precision degree other than
// APPROX will trigger LOGW during the call to `esp_clk_tree_src_get_freq_hz`.
#if SOC_CLK_RC_FAST_SUPPORT_CALIBRATION
@ -435,7 +435,7 @@ static uint32_t ledc_auto_clk_divisor(ledc_mode_t speed_mode, int freq_hz, uint3
uint32_t div_param_timer = ledc_auto_timer_specific_clk_divisor(speed_mode, freq_hz, precision, clk_source);
if (div_param_timer != LEDC_CLK_NOT_FOUND) {
/* The dividor is valid, no need try any other clock, return directly. */
/* The divider is valid, no need try any other clock, return directly. */
ret = div_param_timer;
}
#endif
@ -748,13 +748,13 @@ esp_err_t ledc_stop(ledc_mode_t speed_mode, ledc_channel_t channel, uint32_t idl
}
esp_err_t ledc_set_fade(ledc_mode_t speed_mode, ledc_channel_t channel, uint32_t duty, ledc_duty_direction_t fade_direction,
uint32_t step_num, uint32_t duty_cyle_num, uint32_t duty_scale)
uint32_t step_num, uint32_t duty_cycle_num, uint32_t duty_scale)
{
LEDC_ARG_CHECK(speed_mode < LEDC_SPEED_MODE_MAX, "speed_mode");
LEDC_ARG_CHECK(channel < LEDC_CHANNEL_MAX, "channel");
LEDC_ARG_CHECK(fade_direction < LEDC_DUTY_DIR_MAX, "fade_direction");
LEDC_ARG_CHECK(step_num <= LEDC_LL_DUTY_NUM_MAX, "step_num");
LEDC_ARG_CHECK(duty_cyle_num <= LEDC_LL_DUTY_CYCLE_MAX, "duty_cycle_num");
LEDC_ARG_CHECK(duty_cycle_num <= LEDC_LL_DUTY_CYCLE_MAX, "duty_cycle_num");
LEDC_ARG_CHECK(duty_scale <= LEDC_LL_DUTY_SCALE_MAX, "duty_scale");
LEDC_CHECK(p_ledc_obj[speed_mode] != NULL, LEDC_NOT_INIT, ESP_ERR_INVALID_STATE);
_ledc_fade_hw_acquire(speed_mode, channel);
@ -765,7 +765,7 @@ esp_err_t ledc_set_fade(ledc_mode_t speed_mode, ledc_channel_t channel, uint32_t
duty, //uint32_t duty_val,
fade_direction, //uint32_t increase,
step_num, //uint32_t duty_num,
duty_cyle_num, //uint32_t duty_cycle,
duty_cycle_num, //uint32_t duty_cycle,
duty_scale //uint32_t duty_scale
);
portEXIT_CRITICAL(&ledc_spinlock);
@ -1260,7 +1260,7 @@ esp_err_t ledc_fade_stop(ledc_mode_t speed_mode, ledc_channel_t channel)
}
portEXIT_CRITICAL(&ledc_spinlock);
if (wait_for_idle) {
// Wait for ISR return, which gives the semaphore and switchs state to IDLE
// Wait for ISR return, which gives the semaphore and switches state to IDLE
_ledc_fade_hw_acquire(speed_mode, channel);
assert(fade->fsm == LEDC_FSM_IDLE);
}

Wyświetl plik

@ -379,7 +379,7 @@ TEST_CASE("LEDC fade stop test", "[ledc]")
// Get duty value right before stopping the fade
uint32_t duty_before_stop = ledc_get_duty(test_speed_mode, LEDC_CHANNEL_0);
TEST_ESP_OK(ledc_fade_stop(test_speed_mode, LEDC_CHANNEL_0));
// PWM signal is 2000 Hz. It may take one cycle (500 us) at maximum to stablize the duty.
// PWM signal is 2000 Hz. It may take one cycle (500 us) at maximum to stabilize the duty.
esp_rom_delay_us(500);
// Get duty value now, which is at least one cycle after the ledc_fade_stop function returns
uint32_t duty_after_stop = ledc_get_duty(test_speed_mode, LEDC_CHANNEL_0);
@ -508,7 +508,7 @@ static void tear_testbench(void)
// use PCNT to test the waveform of LEDC
static int wave_count(int last_time)
{
// The input ability of PULSE_IO is disabled after ledc driver install, so we need to reenable it again
// The input ability of PULSE_IO is disabled after ledc driver install, so we need to re-enable it again
PIN_INPUT_ENABLE(GPIO_PIN_MUX_REG[PULSE_IO]);
int test_counter = 0;
TEST_ESP_OK(pcnt_unit_clear_count(pcnt_unit));

Wyświetl plik

@ -20,6 +20,6 @@ menu "ESP-Driver:MCPWM Configurations"
bool "Enable debug log"
default n
help
Wether to enable the debug log message for MCPWM driver.
whether to enable the debug log message for MCPWM driver.
Note that, this option only controls the MCPWM driver log, won't affect other drivers.
endmenu

Wyświetl plik

@ -96,7 +96,7 @@ esp_err_t mcpwm_operator_set_brake_on_fault(mcpwm_oper_handle_t oper, const mcpw
/**
* @brief Try to make the operator recover from fault
*
* @note To recover from fault or escape from trip, you make sure the fault signal has dissappeared already.
* @note To recover from fault or escape from trip, you make sure the fault signal has disappeared already.
* Otherwise the recovery can't succeed.
*
* @param[in] oper MCPWM operator, allocated by `mcpwm_new_operator()`

Wyświetl plik

@ -277,7 +277,7 @@ esp_err_t mcpwm_new_capture_channel(mcpwm_cap_timer_handle_t cap_timer, const mc
// if interrupt priority specified before, it cannot be changed until the group is released
// check if the new priority specified consistents with the old one
ESP_GOTO_ON_ERROR(mcpwm_check_intr_priority(group, config->intr_priority), err, TAG, "set group intrrupt priority failed");
ESP_GOTO_ON_ERROR(mcpwm_check_intr_priority(group, config->intr_priority), err, TAG, "set group interrupt priority failed");
mcpwm_ll_capture_enable_negedge(hal->dev, cap_chan_id, config->flags.neg_edge);
mcpwm_ll_capture_enable_posedge(hal->dev, cap_chan_id, config->flags.pos_edge);

Wyświetl plik

@ -109,7 +109,7 @@ esp_err_t mcpwm_new_gpio_fault(const mcpwm_gpio_fault_config_t *config, mcpwm_fa
// if interrupt priority specified before, it cannot be changed until the group is released
// check if the new priority specified consistents with the old one
ESP_GOTO_ON_ERROR(mcpwm_check_intr_priority(group, config->intr_priority), err, TAG, "set group intrrupt priority failed");
ESP_GOTO_ON_ERROR(mcpwm_check_intr_priority(group, config->intr_priority), err, TAG, "set group interrupt priority failed");
// GPIO configuration
gpio_config_t gpio_conf = {

Wyświetl plik

@ -106,7 +106,7 @@ esp_err_t mcpwm_new_operator(const mcpwm_operator_config_t *config, mcpwm_oper_h
// if interrupt priority specified before, it cannot be changed until the group is released
// check if the new priority specified consistents with the old one
ESP_GOTO_ON_ERROR(mcpwm_check_intr_priority(group, config->intr_priority), err, TAG, "set group intrrupt priority failed");
ESP_GOTO_ON_ERROR(mcpwm_check_intr_priority(group, config->intr_priority), err, TAG, "set group interrupt priority failed");
// reset MCPWM operator
mcpwm_hal_operator_reset(hal, oper_id);

Wyświetl plik

@ -113,7 +113,7 @@ esp_err_t mcpwm_new_timer(const mcpwm_timer_config_t *config, mcpwm_timer_handle
// if interrupt priority specified before, it cannot be changed until the group is released
// check if the new priority specified consistents with the old one
ESP_GOTO_ON_ERROR(mcpwm_check_intr_priority(group, config->intr_priority), err, TAG, "set group intrrupt priority failed");
ESP_GOTO_ON_ERROR(mcpwm_check_intr_priority(group, config->intr_priority), err, TAG, "set group interrupt priority failed");
// select the clock source
mcpwm_timer_clock_source_t clk_src = config->clk_src ? config->clk_src : MCPWM_TIMER_CLK_SRC_DEFAULT;

Wyświetl plik

@ -144,7 +144,7 @@ TEST_CASE("mcpwm_gpio_sync_timer_phase_lock", "[mcpwm]")
sync_phase_config.sync_src = gpio_sync_src;
TEST_ESP_OK(mcpwm_timer_set_phase_on_sync(timers[0], &sync_phase_config));
// simulate an GPIO sync singal
// simulate an GPIO sync signal
gpio_set_level(gpio_num, 1);
gpio_set_level(gpio_num, 0);
check_mcpwm_timer_phase(timers, SOC_MCPWM_CAPTURE_TIMERS_PER_GROUP, 100, MCPWM_TIMER_DIRECTION_UP);

Wyświetl plik

@ -5,7 +5,7 @@ menu "ESP-Driver:Parallel IO Configurations"
bool "Enable debug log"
default n
help
Wether to enable the debug log message for parallel IO driver.
whether to enable the debug log message for parallel IO driver.
Note that, this option only controls the parallel IO driver log, won't affect other drivers.
config PARLIO_ISR_IRAM_SAFE

Wyświetl plik

@ -129,7 +129,7 @@ typedef struct {
uint32_t start_bit_included: 1; /*!< Whether data bit is included in the start pulse */
uint32_t end_bit_included: 1; /*!< Whether data bit is included in the end pulse, only valid when `has_end_pulse` is true */
uint32_t has_end_pulse: 1; /*!< Whether there's an end pulse to terminate the transaction,
if no, the transaction will be terminated by user configured transcation length */
if no, the transaction will be terminated by user configured transaction length */
uint32_t pulse_invert: 1; /*!< Whether to invert the pulse */
} flags; /*!< Extra flags */
} parlio_rx_pulse_delimiter_config_t;

Wyświetl plik

@ -158,7 +158,7 @@ typedef struct {
/**
* @brief Transmit data on by Parallel IO TX unit
*
* @note After the function returns, it doesn't mean the transaction is finished. This function only constructs a transcation structure and push into a queue.
* @note After the function returns, it doesn't mean the transaction is finished. This function only constructs a transaction structure and push into a queue.
*
* @param[in] tx_unit Parallel IO TX unit that created by `parlio_new_tx_unit`
* @param[in] payload Pointer to the data to be transmitted

Wyświetl plik

@ -120,7 +120,7 @@ typedef struct parlio_rx_delimiter_t {
uint32_t start_bit_included: 1; /*!< Whether data bit is included in the start pulse */
uint32_t end_bit_included: 1; /*!< Whether data bit is included in the end pulse, only valid when `has_end_pulse` is true */
uint32_t has_end_pulse: 1; /*!< Whether there's an end pulse to terminate the transaction,
if no, the transaction will be terminated by user configured transcation length */
if no, the transaction will be terminated by user configured transaction length */
uint32_t pulse_invert: 1; /*!< Whether to invert the pulse */
} flags;
} parlio_rx_delimiter_t;
@ -642,7 +642,7 @@ esp_err_t parlio_rx_unit_enable(parlio_rx_unit_handle_t rx_unit, bool reset_queu
ESP_GOTO_ON_FALSE(!rx_unit->is_enabled, ESP_ERR_INVALID_STATE, err, TAG, "the unit has enabled or running");
rx_unit->is_enabled = true;
/* Acquire the power management lock incase */
/* Acquire the power management lock in case */
if (rx_unit->pm_lock) {
esp_pm_lock_acquire(rx_unit->pm_lock);
}

Wyświetl plik

@ -19,7 +19,7 @@ menu "ESP-Driver:PCNT Configurations"
bool "Suppress legacy driver deprecated warning"
default n
help
Wether to suppress the deprecation warnings when using legacy PCNT driver (driver/pcnt.h).
whether to suppress the deprecation warnings when using legacy PCNT driver (driver/pcnt.h).
If you want to continue using the legacy driver, and don't want to see related deprecation warnings,
you can enable this option.
@ -27,6 +27,6 @@ menu "ESP-Driver:PCNT Configurations"
bool "Enable debug log"
default n
help
Wether to enable the debug log message for PCNT driver.
whether to enable the debug log message for PCNT driver.
Note that, this option only controls the PCNT driver log, won't affect other drivers.
endmenu

Wyświetl plik

@ -161,7 +161,7 @@ typedef struct {
* @return
* - ESP_OK: Set clear signal successfully
* - ESP_ERR_INVALID_ARG: Set clear signal failed because of invalid argument
* - ESP_ERR_INVALID_STATE: Set clear signal failed because set clear signal repeatly or disable clear signal before set it
* - ESP_ERR_INVALID_STATE: Set clear signal failed because set clear signal repeatedly or disable clear signal before set it
* - ESP_FAIL: Set clear signal failed because of other error
*/
esp_err_t pcnt_unit_set_clear_signal(pcnt_unit_handle_t unit, const pcnt_clear_signal_config_t *config);

Wyświetl plik

@ -32,7 +32,7 @@ TEST_CASE("pcnt_unit_install_uninstall", "[pcnt]")
TEST_ASSERT_EQUAL(0, count_value);
}
// unit with a different intrrupt priority
// unit with a different interrupt priority
unit_config.intr_priority = 3;
TEST_ESP_ERR(ESP_ERR_INVALID_STATE, pcnt_new_unit(&unit_config, &units[SOC_PCNT_UNITS_PER_GROUP - 1]));
unit_config.intr_priority = 0;

Wyświetl plik

@ -22,6 +22,6 @@ menu "ESP-Driver:RMT Configurations"
bool "Enable debug log"
default n
help
Wether to enable the debug log message for RMT driver.
whether to enable the debug log message for RMT driver.
Note that, this option only controls the RMT driver log, won't affect other drivers.
endmenu

Wyświetl plik

@ -52,7 +52,7 @@ static size_t IRAM_ATTR rmt_encode_bytes(rmt_encoder_t *encoder, rmt_channel_han
{
rmt_bytes_encoder_t *bytes_encoder = __containerof(encoder, rmt_bytes_encoder_t, base);
rmt_tx_channel_t *tx_chan = __containerof(channel, rmt_tx_channel_t, base);
const uint8_t *nd = (const uint8_t *)primary_data;
const uint8_t *raw_data = (const uint8_t *)primary_data;
rmt_encode_state_t state = RMT_ENCODING_RESET;
rmt_dma_descriptor_t *desc0 = NULL;
rmt_dma_descriptor_t *desc1 = NULL;
@ -87,7 +87,7 @@ static size_t IRAM_ATTR rmt_encode_bytes(rmt_encoder_t *encoder, rmt_channel_han
size_t len = encode_len;
while (len > 0) {
// start from last time truncated encoding
uint8_t cur_byte = nd[byte_index];
uint8_t cur_byte = raw_data[byte_index];
// bit-wise reverse
if (bytes_encoder->flags.msb_first) {
cur_byte = hal_utils_bitwise_reverse8(cur_byte);
@ -313,7 +313,7 @@ esp_err_t rmt_encoder_reset(rmt_encoder_handle_t encoder)
return encoder->reset(encoder);
}
void* rmt_alloc_encoder_mem(size_t size)
void *rmt_alloc_encoder_mem(size_t size)
{
return heap_caps_calloc(1, size, RMT_MEM_ALLOC_CAPS);
}

Wyświetl plik

@ -273,7 +273,7 @@ esp_err_t rmt_new_rx_channel(const rmt_rx_channel_config_t *config, rmt_channel_
rmt_ll_rx_enable_wrap(hal->regs, channel_id, true);
#endif
#if SOC_RMT_SUPPORT_RX_DEMODULATION
// disable carrier demodulation by default, can reenable by `rmt_apply_carrier()`
// disable carrier demodulation by default, can re-enable by `rmt_apply_carrier()`
rmt_ll_rx_enable_carrier_demodulation(hal->regs, channel_id, false);
#endif

Wyświetl plik

@ -329,7 +329,7 @@ esp_err_t rmt_new_tx_channel(const rmt_tx_channel_config_t *config, rmt_channel_
rmt_ll_tx_set_mem_blocks(hal->regs, channel_id, tx_channel->base.mem_block_num);
// set limit threshold, after transmit ping_pong_symbols size, an interrupt event would be generated
rmt_ll_tx_set_limit(hal->regs, channel_id, tx_channel->ping_pong_symbols);
// disable carrier modulation by default, can reenable by `rmt_apply_carrier()`
// disable carrier modulation by default, can re-enable by `rmt_apply_carrier()`
rmt_ll_tx_enable_carrier_modulation(hal->regs, channel_id, false);
// idle level is determined by register value
rmt_ll_tx_fix_idle_level(hal->regs, channel_id, 0, true);

Wyświetl plik

@ -42,7 +42,7 @@ static void test_rmt_tx_iram_safe(size_t mem_block_symbols, bool with_dma)
printf("enable tx channel\r\n");
TEST_ESP_OK(rmt_enable(tx_channel_multi_leds));
// Mutiple LEDs (ping-pong in the background)
// Multiple LEDs (ping-pong in the background)
printf("ping pong transmission: light up 100 RGB LEDs\r\n");
rmt_transmit_config_t transmit_config = {
.loop_count = 0, // no loop

Wyświetl plik

@ -162,7 +162,7 @@ static void test_rmt_ping_pong_trans(size_t mem_block_symbols, bool with_dma)
printf("enable tx channel\r\n");
TEST_ESP_OK(rmt_enable(tx_channel_multi_leds));
// Mutiple LEDs (ping-pong in the background)
// Multiple LEDs (ping-pong in the background)
printf("ping pong transmission: light up %d RGB LEDs\r\n", test_led_num);
rmt_transmit_config_t transmit_config = {
.loop_count = 0, // no loop

Wyświetl plik

@ -113,7 +113,7 @@ typedef struct recv_desc_s {
// first 3 WORDs of this struct is defined by and compatible to the DMA link list format.
uint32_t _reserved0;
uint32_t _reserved1;
TAILQ_ENTRY(recv_desc_s) te; // tailq used to store the registered descriptors.
TAILQ_ENTRY(recv_desc_s) tail_entry; // tailq used to store the registered descriptors.
};
};
} recv_desc_t;
@ -367,8 +367,8 @@ void sdio_slave_deinit(void)
//unregister all buffers registered but returned (not loaded)
recv_desc_t *temp_desc;
recv_desc_t *desc;
TAILQ_FOREACH_SAFE(desc, &context.recv_reg_list, te, temp_desc) {
TAILQ_REMOVE(&context.recv_reg_list, desc, te);
TAILQ_FOREACH_SAFE(desc, &context.recv_reg_list, tail_entry, temp_desc) {
TAILQ_REMOVE(&context.recv_reg_list, desc, tail_entry);
free(desc);
}
//unregister all buffers that is loaded and not returned
@ -719,7 +719,7 @@ esp_err_t sdio_slave_recv_load_buf(sdio_slave_buf_handle_t handle)
assert(desc->not_receiving);
critical_enter_recv();
TAILQ_REMOVE(&context.recv_reg_list, desc, te);
TAILQ_REMOVE(&context.recv_reg_list, desc, tail_entry);
desc->not_receiving = 0; //manually remove the prev link (by set not_receiving=0), to indicate this is in the queue
sdio_slave_hal_load_buf(context.hal, &desc->hal_desc);
critical_exit_recv();
@ -739,7 +739,7 @@ sdio_slave_buf_handle_t sdio_slave_recv_register_buf(uint8_t *start)
//initially in the reg list
sdio_slave_hal_recv_init_desc(context.hal, &desc->hal_desc, start);
critical_enter_recv();
TAILQ_INSERT_TAIL(&context.recv_reg_list, desc, te);
TAILQ_INSERT_TAIL(&context.recv_reg_list, desc, tail_entry);
critical_exit_recv();
return desc;
}
@ -748,7 +748,7 @@ esp_err_t sdio_slave_recv(sdio_slave_buf_handle_t *handle_ret, uint8_t **out_add
{
esp_err_t ret = sdio_slave_recv_packet(handle_ret, wait);
if (ret == ESP_ERR_NOT_FINISHED) {
//This API was not awared of the EOF info, return ESP_OK to keep back-compatible.
//This API was not aware of the EOF info, return ESP_OK to keep back-compatible.
ret = ESP_OK;
}
if (ret == ESP_OK) {
@ -776,7 +776,7 @@ esp_err_t sdio_slave_recv_packet(sdio_slave_buf_handle_t *handle_ret, TickType_t
//remove from queue, add back to reg list.
recv_desc_t *desc = (recv_desc_t *)sdio_slave_hal_recv_unload_desc(context.hal);
assert(desc != NULL && desc->hal_desc.owner == 0);
TAILQ_INSERT_TAIL(&context.recv_reg_list, desc, te);
TAILQ_INSERT_TAIL(&context.recv_reg_list, desc, tail_entry);
critical_exit_recv();
*handle_ret = (sdio_slave_buf_handle_t)desc;
@ -793,7 +793,7 @@ esp_err_t sdio_slave_recv_unregister_buf(sdio_slave_buf_handle_t handle)
CHECK_HANDLE_IDLE(desc); //in the queue, fail.
critical_enter_recv();
TAILQ_REMOVE(&context.recv_reg_list, desc, te);
TAILQ_REMOVE(&context.recv_reg_list, desc, tail_entry);
critical_exit_recv();
free(desc);
return ESP_OK;

Wyświetl plik

@ -12,7 +12,7 @@ menu "ESP-Driver:Sigma Delta Modulator Configurations"
bool "Suppress legacy driver deprecated warning"
default n
help
Wether to suppress the deprecation warnings when using legacy sigma delta driver.
whether to suppress the deprecation warnings when using legacy sigma delta driver.
If you want to continue using the legacy driver, and don't want to see related deprecation warnings,
you can enable this option.
@ -20,6 +20,6 @@ menu "ESP-Driver:Sigma Delta Modulator Configurations"
bool "Enable debug log"
default n
help
Wether to enable the debug log message for SDM driver.
whether to enable the debug log message for SDM driver.
Note that, this option only controls the SDM driver log, won't affect other drivers.
endmenu # Sigma Delta Modulator Configurations

Wyświetl plik

@ -34,7 +34,7 @@
/// Data rejected due to write error
#define TOKEN_RSP_WRITE_ERR 0b01101
/// Data error tokens have format 0b0000xyzw where xyzw are signle bit flags.
/// Data error tokens have format 0b0000xyzw where xyzw are single bit flags.
/// MASK and VAL are used to check if a token is an error token
#define TOKEN_ERR_MASK 0b11110000
#define TOKEN_ERR_VAL 0b00000000

Wyświetl plik

@ -92,7 +92,7 @@ typedef spi_common_dma_t spi_dma_chan_t;
* the IO_MUX or are -1. In that case, the IO_MUX is used. On ESP32, using GPIO matrix will bring about 25ns of input
* delay, which may cause incorrect read for >40MHz speeds.
*
* @note Be advised that the slave driver does not use the quadwp/quadhd lines and fields in spi_bus_config_t refering to these lines will be ignored and can thus safely be left uninitialized.
* @note Be advised that the slave driver does not use the quadwp/quadhd lines and fields in spi_bus_config_t referring to these lines will be ignored and can thus safely be left uninitialized.
*/
typedef struct {
union {

Wyświetl plik

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2010-2021 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2010-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -223,9 +223,9 @@ esp_err_t spi_device_queue_trans(spi_device_handle_t handle, spi_transaction_t *
* @brief Get the result of a SPI transaction queued earlier by ``spi_device_queue_trans``.
*
* This routine will wait until a transaction to the given device
* succesfully completed. It will then return the description of the
* successfully completed. It will then return the description of the
* completed transaction so software can inspect the result and e.g. free the memory or
* re-use the buffers.
* reuse the buffers.
*
* @param handle Device handle obtained using spi_host_add_dev
* @param trans_desc Pointer to variable able to contain a pointer to the description of the transaction
@ -286,7 +286,7 @@ esp_err_t spi_device_polling_start(spi_device_handle_t handle, spi_transaction_t
* @brief Poll until the polling transaction ends.
*
* This routine will not return until the transaction to the given device has
* succesfully completed. The task is not blocked, but actively busy-spins for
* successfully completed. The task is not blocked, but actively busy-spins for
* the transaction to be completed.
*
* @param handle Device handle obtained using spi_host_add_dev
@ -385,7 +385,7 @@ void spi_get_timing(bool gpio_is_used, int input_delay_ns, int eff_clk, int *dum
/**
* @brief Get the frequency limit of current configurations.
* SPI master working at this limit is OK, while above the limit, full duplex mode and DMA will not work,
* and dummy bits will be aplied in the half duplex mode.
* and dummy bits will be applied in the half duplex mode.
*
* @param gpio_is_used True if using GPIO matrix, or False if native pins are used.
* @param input_delay_ns Input delay from SCLK launch edge to MISO data valid.

Wyświetl plik

@ -149,9 +149,9 @@ esp_err_t spi_slave_queue_trans(spi_host_device_t host, const spi_slave_transact
* @brief Get the result of a SPI transaction queued earlier
*
* This routine will wait until a transaction to the given device (queued earlier with
* spi_slave_queue_trans) has succesfully completed. It will then return the description of the
* spi_slave_queue_trans) has successfully completed. It will then return the description of the
* completed transaction so software can inspect the result and e.g. free the memory or
* re-use the buffers.
* reuse the buffers.
*
* It is mandatory to eventually use this function for any transaction queued by ``spi_slave_queue_trans``.
*

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