Merge branch 'bugfix/rmt_iram_safe_test_5.0' into 'release/v5.0'

driver: multiple updates backport to (5.0)

See merge request espressif/esp-idf!19525
This commit is contained in:
morris
2022-08-22 19:02:08 +08:00
158 changed files with 940 additions and 1534 deletions

View File

@@ -44,6 +44,7 @@ extern "C" {
#endif
#include <stdbool.h>
#include <stddef.h>
typedef struct linenoiseCompletions {
size_t len;

View File

@@ -125,5 +125,3 @@ else()
REQUIRES esp_pm esp_ringbuf freertos soc hal esp_hw_support
LDFRAGMENTS linker.lf)
endif()
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

View File

@@ -535,7 +535,7 @@ static esp_err_t i2s_alloc_dma_buffer(i2s_port_t i2s_num, i2s_dma_t *dma_obj)
if (p_i2s[i2s_num]->dir & I2S_DIR_RX) {
i2s_ll_rx_set_eof_num(p_i2s[i2s_num]->hal.dev, dma_obj->buf_size);
}
ESP_LOGD(TAG, "DMA Malloc info, datalen=blocksize=%d, dma_desc_num=%d", dma_obj->buf_size, buf_cnt);
ESP_LOGD(TAG, "DMA Malloc info, datalen=blocksize=%d, dma_desc_num=%"PRIu32, dma_obj->buf_size, buf_cnt);
return ESP_OK;
err:
/* Delete DMA buffer if failed to allocate memory */
@@ -644,9 +644,9 @@ static uint32_t i2s_config_source_clock(i2s_port_t i2s_num, bool use_apll, uint3
return 0;
}
if (ret == ESP_ERR_INVALID_STATE) {
ESP_LOGW(TAG, "APLL is occupied already, it is working at %d Hz", real_freq);
ESP_LOGW(TAG, "APLL is occupied already, it is working at %"PRIu32" Hz", real_freq);
}
ESP_LOGD(TAG, "APLL expected frequency is %d Hz, real frequency is %d Hz", expt_freq, real_freq);
ESP_LOGD(TAG, "APLL expected frequency is %"PRIu32" Hz, real frequency is %"PRIu32" Hz", expt_freq, real_freq);
/* In APLL mode, there is no sclk but only mclk, so return 0 here to indicate APLL mode */
return real_freq;
}
@@ -804,7 +804,7 @@ static esp_err_t i2s_calculate_clock(i2s_port_t i2s_num, i2s_hal_clock_info_t *c
/* Calculate clock for common mode */
ESP_RETURN_ON_ERROR(i2s_calculate_common_clock(i2s_num, clk_info), TAG, "Common clock calculate failed");
ESP_LOGD(TAG, "[sclk] %d [mclk] %d [mclk_div] %d [bclk] %d [bclk_div] %d",
ESP_LOGD(TAG, "[sclk] %"PRIu32" [mclk] %"PRIu32" [mclk_div] %d [bclk] %"PRIu32" [bclk_div] %d",
clk_info->sclk, clk_info->mclk, clk_info->mclk_div, clk_info->bclk, clk_info->bclk_div);
return ESP_OK;
}
@@ -1077,7 +1077,7 @@ esp_err_t i2s_set_clk(i2s_port_t i2s_num, uint32_t rate, uint32_t bits_cfg, i2s_
slot_mask = (slot_cfg->slot_mode == I2S_SLOT_MODE_MONO) ? 1 : 2;
}
ESP_RETURN_ON_FALSE(p_i2s[i2s_num]->total_slot >= (32 - __builtin_clz(slot_mask)), ESP_ERR_INVALID_ARG, TAG,
"The max channel number can't be greater than CH%d\n", p_i2s[i2s_num]->total_slot);
"The max channel number can't be greater than CH%"PRIu32, p_i2s[i2s_num]->total_slot);
p_i2s[i2s_num]->active_slot = __builtin_popcount(slot_mask);
} else
#endif

View File

@@ -787,7 +787,7 @@ esp_err_t mcpwm_capture_enable_channel(mcpwm_unit_t mcpwm_num, mcpwm_capture_cha
mcpwm_ll_capture_enable_negedge(hal->dev, cap_channel, cap_conf->cap_edge & MCPWM_NEG_EDGE);
mcpwm_ll_capture_enable_posedge(hal->dev, cap_channel, cap_conf->cap_edge & MCPWM_POS_EDGE);
mcpwm_ll_capture_set_prescale(hal->dev, cap_channel, cap_conf->cap_prescale);
// capture feature should be used with interupt, so enable it by default
// capture feature should be used with interrupt, so enable it by default
mcpwm_ll_intr_enable(hal->dev, MCPWM_LL_EVENT_CAPTURE(cap_channel), true);
mcpwm_ll_intr_clear_capture_status(hal->dev, 1 << cap_channel);
mcpwm_critical_exit(mcpwm_num);

View File

@@ -586,11 +586,11 @@ static esp_err_t rmt_internal_config(rmt_dev_t *dev, const rmt_config_t *rmt_par
s_rmt_source_clock_hz[channel] = rmt_source_clk_hz;
#else
if (s_rmt_source_clock_hz && rmt_source_clk_hz != s_rmt_source_clock_hz) {
ESP_LOGW(TAG, "RMT clock source has been configured to %d by other channel, now reconfigure it to %d", s_rmt_source_clock_hz, rmt_source_clk_hz);
ESP_LOGW(TAG, "RMT clock source has been configured to %"PRIu32" by other channel, now reconfigure it to %"PRIu32, s_rmt_source_clock_hz, rmt_source_clk_hz);
}
s_rmt_source_clock_hz = rmt_source_clk_hz;
#endif
ESP_LOGD(TAG, "rmt_source_clk_hz: %d\n", rmt_source_clk_hz);
ESP_LOGD(TAG, "rmt_source_clk_hz: %"PRIu32, rmt_source_clk_hz);
if (mode == RMT_MODE_TX) {
uint16_t carrier_duty_percent = rmt_param->tx_config.carrier_duty_percent;
@@ -625,7 +625,7 @@ static esp_err_t rmt_internal_config(rmt_dev_t *dev, const rmt_config_t *rmt_par
}
RMT_EXIT_CRITICAL();
ESP_LOGD(TAG, "Rmt Tx Channel %u|Gpio %u|Sclk_Hz %u|Div %u|Carrier_Hz %u|Duty %u",
ESP_LOGD(TAG, "Rmt Tx Channel %u|Gpio %u|Sclk_Hz %"PRIu32"|Div %u|Carrier_Hz %"PRIu32"|Duty %u",
channel, gpio_num, rmt_source_clk_hz, clk_div, carrier_freq_hz, carrier_duty_percent);
} else if (RMT_MODE_RX == mode) {
uint8_t filter_cnt = rmt_param->rx_config.filter_ticks_thresh;
@@ -659,7 +659,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 %u|Div %u|Thresold %u|Filter %u",
ESP_LOGD(TAG, "Rmt Rx Channel %u|Gpio %u|Sclk_Hz %"PRIu32"|Div %u|Thresold %u|Filter %u",
channel, gpio_num, rmt_source_clk_hz, clk_div, threshold, filter_cnt);
}
@@ -936,13 +936,9 @@ esp_err_t rmt_driver_uninstall(rmt_channel_t channel)
RMT_ENTER_CRITICAL();
// check channel's working mode
if (p_rmt_obj[channel]->rx_buf) {
rmt_ll_enable_interrupt(rmt_contex.hal.regs, RMT_LL_EVENT_RX_DONE(RMT_DECODE_RX_CHANNEL(channel)), false);
rmt_ll_enable_interrupt(rmt_contex.hal.regs, RMT_LL_EVENT_RX_ERROR(RMT_DECODE_RX_CHANNEL(channel)), false);
#if SOC_RMT_SUPPORT_RX_PINGPONG
rmt_ll_enable_interrupt(rmt_contex.hal.regs, RMT_LL_EVENT_RX_THRES(RMT_DECODE_RX_CHANNEL(channel)), false);
#endif
rmt_ll_enable_interrupt(rmt_contex.hal.regs, RMT_LL_EVENT_RX_MASK(RMT_DECODE_RX_CHANNEL(channel)) | RMT_LL_EVENT_RX_ERROR(RMT_DECODE_RX_CHANNEL(channel)), false);
} else {
rmt_ll_enable_interrupt(rmt_contex.hal.regs, RMT_LL_EVENT_TX_DONE(channel) | RMT_LL_EVENT_TX_ERROR(channel) | RMT_LL_EVENT_TX_THRES(channel), false);
rmt_ll_enable_interrupt(rmt_contex.hal.regs, RMT_LL_EVENT_TX_MASK(channel) | RMT_LL_EVENT_TX_ERROR(channel), false);
}
RMT_EXIT_CRITICAL();
@@ -1001,10 +997,10 @@ esp_err_t rmt_driver_install(rmt_channel_t channel, size_t rx_buf_size, int intr
}
#if CONFIG_RINGBUF_PLACE_ISR_FUNCTIONS_INTO_FLASH
if (intr_alloc_flags & ESP_INTR_FLAG_IRAM ) {
ESP_LOGE(TAG, "ringbuf ISR functions in flash, but used in IRAM interrupt");
return ESP_ERR_INVALID_ARG;
}
if (intr_alloc_flags & ESP_INTR_FLAG_IRAM ) {
ESP_LOGE(TAG, "ringbuf ISR functions in flash, but used in IRAM interrupt");
return ESP_ERR_INVALID_ARG;
}
#endif
#if !CONFIG_SPIRAM_USE_MALLOC

View File

@@ -145,7 +145,7 @@ esp_err_t temp_sensor_read_celsius(float *celsius)
uint32_t tsens_out = 0;
temp_sensor_get_config(&tsens);
temp_sensor_read_raw(&tsens_out);
ESP_LOGV(TAG, "tsens_out %d", tsens_out);
ESP_LOGV(TAG, "tsens_out %"PRIu32, tsens_out);
const tsens_dac_offset_t *dac = &dac_offset[tsens.dac_offset];
*celsius = parse_temp_sensor_raw_value(tsens_out, dac->offset);
if (*celsius < dac->range_min || *celsius > dac->range_max) {

View File

@@ -67,7 +67,7 @@ struct dedic_gpio_bundle_t {
int gpio_array[]; // array of GPIO numbers (configured by user)
};
static esp_err_t dedic_gpio_build_platform(uint32_t core_id)
static esp_err_t dedic_gpio_build_platform(int core_id)
{
esp_err_t ret = ESP_OK;
if (!s_platform[core_id]) {
@@ -196,7 +196,7 @@ esp_err_t dedic_gpio_new_bundle(const dedic_gpio_bundle_config_t *config, dedic_
dedic_gpio_bundle_t *bundle = NULL;
uint32_t out_mask = 0;
uint32_t in_mask = 0;
uint32_t core_id = esp_cpu_get_core_id(); // dedicated GPIO will be binded to the CPU who invokes this API
int core_id = esp_cpu_get_core_id(); // dedicated GPIO will be binded to the CPU who invokes this API
ESP_GOTO_ON_FALSE(config && ret_bundle, ESP_ERR_INVALID_ARG, err, TAG, "invalid argument");
ESP_GOTO_ON_FALSE(config->gpio_array && config->array_size > 0, ESP_ERR_INVALID_ARG, err, TAG, "invalid GPIO array or size");
@@ -233,7 +233,7 @@ esp_err_t dedic_gpio_new_bundle(const dedic_gpio_bundle_config_t *config, dedic_
}
portEXIT_CRITICAL(&s_platform[core_id]->spinlock);
ESP_GOTO_ON_FALSE(out_mask, ESP_ERR_NOT_FOUND, err, TAG, "no free outward channels on core[%d]", core_id);
ESP_LOGD(TAG, "new outward bundle(%p) on core[%d], offset=%d, mask(%x)", bundle, core_id, out_offset, out_mask);
ESP_LOGD(TAG, "new outward bundle(%p) on core[%d], offset=%"PRIu32", mask(%"PRIx32")", bundle, core_id, out_offset, out_mask);
}
// configure inwards channels
@@ -255,7 +255,7 @@ esp_err_t dedic_gpio_new_bundle(const dedic_gpio_bundle_config_t *config, dedic_
}
portEXIT_CRITICAL(&s_platform[core_id]->spinlock);
ESP_GOTO_ON_FALSE(in_mask, ESP_ERR_NOT_FOUND, err, TAG, "no free inward channels on core[%d]", core_id);
ESP_LOGD(TAG, "new inward bundle(%p) on core[%d], offset=%d, mask(%x)", bundle, core_id, in_offset, in_mask);
ESP_LOGD(TAG, "new inward bundle(%p) on core[%d], offset=%"PRIu32", mask(%"PRIx32")", bundle, core_id, in_offset, in_mask);
}
// route dedicated GPIO channel signals to GPIO matrix
@@ -377,7 +377,7 @@ esp_err_t dedic_gpio_bundle_set_interrupt_and_callback(dedic_gpio_bundle_handle_
{
esp_err_t ret = ESP_OK;
ESP_GOTO_ON_FALSE(bundle, ESP_ERR_INVALID_ARG, err, TAG, "invalid argument");
uint32_t core_id = esp_cpu_get_core_id();
int core_id = esp_cpu_get_core_id();
// lazy alloc interrupt
ESP_GOTO_ON_ERROR(dedic_gpio_install_interrupt(core_id), err, TAG, "allocate interrupt on core %d failed", core_id);

View File

@@ -371,7 +371,7 @@ esp_err_t gpio_config(const gpio_config_t *pGPIOConfig)
gpio_pulldown_dis(io_num);
}
ESP_LOGI(GPIO_TAG, "GPIO[%d]| InputEn: %d| OutputEn: %d| OpenDrain: %d| Pullup: %d| Pulldown: %d| Intr:%d ", io_num, input_en, output_en, od_en, pu_en, pd_en, pGPIOConfig->intr_type);
ESP_LOGI(GPIO_TAG, "GPIO[%"PRIu32"]| InputEn: %d| OutputEn: %d| OpenDrain: %d| Pullup: %d| Pulldown: %d| Intr:%d ", io_num, input_en, output_en, od_en, pu_en, pd_en, pGPIOConfig->intr_type);
gpio_set_intr_type(io_num, pGPIOConfig->intr_type);
if (pGPIOConfig->intr_type) {

View File

@@ -71,9 +71,9 @@ typedef enum {
struct gptimer_t {
gptimer_group_t *group;
int timer_id;
unsigned int resolution_hz;
unsigned long long reload_count;
unsigned long long alarm_count;
uint32_t resolution_hz;
uint64_t reload_count;
uint64_t alarm_count;
gptimer_count_direction_t direction;
timer_hal_context_t hal;
gptimer_fsm_t fsm;
@@ -164,7 +164,7 @@ esp_err_t gptimer_new_timer(const gptimer_config_t *config, gptimer_handle_t *re
esp_err_t ret = ESP_OK;
gptimer_t *timer = NULL;
ESP_GOTO_ON_FALSE(config && ret_timer, ESP_ERR_INVALID_ARG, err, TAG, "invalid argument");
ESP_GOTO_ON_FALSE(config->resolution_hz, ESP_ERR_INVALID_ARG, err, TAG, "invalid timer resolution:%d", config->resolution_hz);
ESP_GOTO_ON_FALSE(config->resolution_hz, ESP_ERR_INVALID_ARG, err, TAG, "invalid timer resolution:%"PRIu32, config->resolution_hz);
timer = heap_caps_calloc(1, sizeof(gptimer_t), GPTIMER_MEM_ALLOC_CAPS);
ESP_GOTO_ON_FALSE(timer, ESP_ERR_NO_MEM, err, TAG, "no mem for gptimer");
@@ -197,7 +197,7 @@ esp_err_t gptimer_new_timer(const gptimer_config_t *config, gptimer_handle_t *re
timer->fsm = GPTIMER_FSM_INIT; // put the timer into init state
timer->direction = config->direction;
timer->flags.intr_shared = config->flags.intr_shared;
ESP_LOGD(TAG, "new gptimer (%d,%d) at %p, resolution=%uHz", group_id, timer_id, timer, timer->resolution_hz);
ESP_LOGD(TAG, "new gptimer (%d,%d) at %p, resolution=%"PRIu32"Hz", group_id, timer_id, timer, timer->resolution_hz);
*ret_timer = timer;
return ESP_OK;
@@ -245,7 +245,6 @@ esp_err_t gptimer_register_event_callbacks(gptimer_handle_t timer, const gptimer
{
gptimer_group_t *group = NULL;
ESP_RETURN_ON_FALSE(timer && cbs, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
ESP_RETURN_ON_FALSE(timer->fsm == GPTIMER_FSM_INIT, ESP_ERR_INVALID_STATE, TAG, "timer not in init state");
group = timer->group;
int group_id = group->group_id;
int timer_id = timer->timer_id;
@@ -261,6 +260,7 @@ esp_err_t gptimer_register_event_callbacks(gptimer_handle_t timer, const gptimer
// lazy install interrupt service
if (!timer->intr) {
ESP_RETURN_ON_FALSE(timer->fsm == GPTIMER_FSM_INIT, ESP_ERR_INVALID_STATE, TAG, "timer not in init state");
// if user wants to control the interrupt allocation more precisely, we can expose more flags in `gptimer_config_t`
int isr_flags = timer->flags.intr_shared ? ESP_INTR_FLAG_SHARED | GPTIMER_INTR_ALLOC_FLAGS : GPTIMER_INTR_ALLOC_FLAGS;
ESP_RETURN_ON_ERROR(esp_intr_alloc_intrstatus(timer_group_periph_signals.groups[group_id].timer_irq_id[timer_id], isr_flags,
@@ -318,7 +318,7 @@ esp_err_t gptimer_enable(gptimer_handle_t timer)
if (timer->pm_lock) {
ESP_RETURN_ON_ERROR(esp_pm_lock_acquire(timer->pm_lock), TAG, "acquire pm_lock failed");
}
// enable interrupt interupt service
// enable interrupt service
if (timer->intr) {
ESP_RETURN_ON_ERROR(esp_intr_enable(timer->intr), TAG, "enable interrupt service failed");
}
@@ -474,7 +474,7 @@ static esp_err_t gptimer_select_periph_clock(gptimer_t *timer, gptimer_clock_sou
timer_ll_set_clock_prescale(timer->hal.dev, timer_id, prescale);
timer->resolution_hz = counter_src_hz / prescale; // this is the real resolution
if (timer->resolution_hz != resolution_hz) {
ESP_LOGW(TAG, "resolution lost, expect %u, real %u", resolution_hz, timer->resolution_hz);
ESP_LOGW(TAG, "resolution lost, expect %"PRIu32", real %"PRIu32, resolution_hz, timer->resolution_hz);
}
return ret;
}

View File

@@ -55,10 +55,10 @@
// If ISR handler is allowed to run whilst cache is disabled,
// Make sure all the code and related variables used by the handler are in the SRAM
#if CONFIG_I2S_ISR_IRAM_SAFE
#define I2S_INTR_ALLOC_FLAGS (ESP_INTR_FLAG_IRAM | ESP_INTR_FLAG_INTRDISABLED | ESP_INTR_FLAG_SHARED)
#define I2S_INTR_ALLOC_FLAGS (ESP_INTR_FLAG_IRAM | ESP_INTR_FLAG_INTRDISABLED | ESP_INTR_FLAG_SHARED | ESP_INTR_FLAG_LOWMED)
#define I2S_MEM_ALLOC_CAPS (MALLOC_CAP_INTERNAL | MALLOC_CAP_8BIT)
#else
#define I2S_INTR_ALLOC_FLAGS (ESP_INTR_FLAG_INTRDISABLED | ESP_INTR_FLAG_SHARED)
#define I2S_INTR_ALLOC_FLAGS (ESP_INTR_FLAG_INTRDISABLED | ESP_INTR_FLAG_SHARED | ESP_INTR_FLAG_LOWMED)
#define I2S_MEM_ALLOC_CAPS MALLOC_CAP_DEFAULT
#endif //CONFIG_I2S_ISR_IRAM_SAFE
#define I2S_DMA_ALLOC_CAPS (MALLOC_CAP_INTERNAL | MALLOC_CAP_DMA)
@@ -371,7 +371,7 @@ uint32_t i2s_get_buf_size(i2s_chan_handle_t handle, uint32_t data_bit_width, uin
if (bufsize > I2S_DMA_BUFFER_MAX_SIZE) {
uint32_t frame_num = I2S_DMA_BUFFER_MAX_SIZE / bytes_per_frame;
bufsize = frame_num * bytes_per_frame;
ESP_LOGW(TAG, "dma frame num is out of dma buffer size, limited to %d", frame_num);
ESP_LOGW(TAG, "dma frame num is out of dma buffer size, limited to %"PRIu32, frame_num);
}
return bufsize;
}
@@ -436,7 +436,7 @@ esp_err_t i2s_alloc_dma_desc(i2s_chan_handle_t handle, uint32_t num, uint32_t bu
if (handle->dir == I2S_DIR_RX) {
i2s_ll_rx_set_eof_num(handle->controller->hal.dev, bufsize);
}
ESP_LOGD(TAG, "DMA malloc info: dma_desc_num = %d, dma_desc_buf_size = dma_frame_num * slot_num * data_bit_width = %d", num, bufsize);
ESP_LOGD(TAG, "DMA malloc info: dma_desc_num = %"PRIu32", dma_desc_buf_size = dma_frame_num * slot_num * data_bit_width = %"PRIu32, num, bufsize);
return ESP_OK;
err:
i2s_free_dma_desc(handle);
@@ -465,10 +465,10 @@ uint32_t i2s_set_get_apll_freq(uint32_t mclk_freq_hz)
return 0;
}
if (ret == ESP_ERR_INVALID_STATE) {
ESP_LOGW(TAG, "APLL is occupied already, it is working at %d Hz while the expected frequency is %d Hz", real_freq, expt_freq);
ESP_LOGW(TAG, "Trying to work at %d Hz...", real_freq);
ESP_LOGW(TAG, "APLL is occupied already, it is working at %"PRIu32" Hz while the expected frequency is %"PRIu32" Hz", real_freq, expt_freq);
ESP_LOGW(TAG, "Trying to work at %"PRIu32" Hz...", real_freq);
}
ESP_LOGD(TAG, "APLL expected frequency is %d Hz, real frequency is %d Hz", expt_freq, real_freq);
ESP_LOGD(TAG, "APLL expected frequency is %"PRIu32" Hz, real frequency is %"PRIu32" Hz", expt_freq, real_freq);
return real_freq;
}
#endif

View File

@@ -61,7 +61,7 @@ static esp_err_t i2s_pdm_tx_set_clock(i2s_chan_handle_t handle, const i2s_pdm_tx
i2s_hal_clock_info_t clk_info;
/* Calculate clock parameters */
ESP_RETURN_ON_ERROR(i2s_pdm_tx_calculate_clock(handle, clk_cfg, &clk_info), TAG, "clock calculate failed");
ESP_LOGD(TAG, "Clock division info: [sclk] %d Hz [mdiv] %d [mclk] %d Hz [bdiv] %d [bclk] %d Hz",
ESP_LOGD(TAG, "Clock division info: [sclk] %"PRIu32" Hz [mdiv] %d [mclk] %"PRIu32" Hz [bdiv] %d [bclk] %"PRIu32" Hz",
clk_info.sclk, clk_info.mclk_div, clk_info.mclk, clk_info.bclk_div, clk_info.bclk);
portENTER_CRITICAL(&g_i2s.spinlock);
@@ -348,7 +348,7 @@ static esp_err_t i2s_pdm_rx_set_clock(i2s_chan_handle_t handle, const i2s_pdm_rx
i2s_hal_clock_info_t clk_info;
/* Calculate clock parameters */
ESP_RETURN_ON_ERROR(i2s_pdm_rx_calculate_clock(handle, clk_cfg, &clk_info), TAG, "clock calculate failed");
ESP_LOGD(TAG, "Clock division info: [sclk] %d Hz [mdiv] %d [mclk] %d Hz [bdiv] %d [bclk] %d Hz",
ESP_LOGD(TAG, "Clock division info: [sclk] %"PRIu32" Hz [mdiv] %d [mclk] %"PRIu32" Hz [bdiv] %d [bclk] %"PRIu32" Hz",
clk_info.sclk, clk_info.mclk_div, clk_info.mclk, clk_info.bclk_div, clk_info.bclk);
portENTER_CRITICAL(&g_i2s.spinlock);

View File

@@ -69,7 +69,7 @@ static esp_err_t i2s_std_set_clock(i2s_chan_handle_t handle, const i2s_std_clk_c
i2s_hal_clock_info_t clk_info;
/* Calculate clock parameters */
ESP_RETURN_ON_ERROR(i2s_std_calculate_clock(handle, clk_cfg, &clk_info), TAG, "clock calculate failed");
ESP_LOGD(TAG, "Clock division info: [sclk] %d Hz [mdiv] %d [mclk] %d Hz [bdiv] %d [bclk] %d Hz",
ESP_LOGD(TAG, "Clock division info: [sclk] %"PRIu32" Hz [mdiv] %d [mclk] %"PRIu32" Hz [bdiv] %d [bclk] %"PRIu32" Hz",
clk_info.sclk, clk_info.mclk_div, clk_info.mclk, clk_info.bclk_div, clk_info.bclk);
portENTER_CRITICAL(&g_i2s.spinlock);

View File

@@ -45,7 +45,7 @@ static esp_err_t i2s_tdm_calculate_clock(i2s_chan_handle_t handle, const i2s_tdm
clk_info->mclk *= 2;
clk_info->bclk_div = clk_info->mclk / clk_info->bclk;
if (clk_info->bclk_div <= 2) {
ESP_LOGW(TAG, "the current mclk multiple is too small, adjust the mclk multiple to %d", clk_info->mclk / rate);
ESP_LOGW(TAG, "the current mclk multiple is too small, adjust the mclk multiple to %"PRIu32, clk_info->mclk / rate);
}
} while (clk_info->bclk_div <= 2);
} else {
@@ -76,7 +76,7 @@ static esp_err_t i2s_tdm_set_clock(i2s_chan_handle_t handle, const i2s_tdm_clk_c
i2s_hal_clock_info_t clk_info;
/* Calculate clock parameters */
ESP_RETURN_ON_ERROR(i2s_tdm_calculate_clock(handle, clk_cfg, &clk_info), TAG, "clock calculate failed");
ESP_LOGD(TAG, "Clock division info: [sclk] %d Hz [mdiv] %d [mclk] %d Hz [bdiv] %d [bclk] %d Hz",
ESP_LOGD(TAG, "Clock division info: [sclk] %"PRIu32" Hz [mdiv] %d [mclk] %"PRIu32" Hz [bdiv] %d [bclk] %"PRIu32" Hz",
clk_info.sclk, clk_info.mclk_div, clk_info.mclk, clk_info.bclk_div, clk_info.bclk);
portENTER_CRITICAL(&g_i2s.spinlock);

View File

@@ -138,7 +138,8 @@ esp_err_t gptimer_get_raw_count(gptimer_handle_t timer, uint64_t *value);
* @brief Set callbacks for GPTimer
*
* @note User registered callbacks are expected to be runnable within ISR context
* @note This function should be called when the timer is in the init state (i.e. before calling `gptimer_enable()`)
* @note The first call to this function needs to be before the call to `gptimer_enable`
* @note User can deregister a previously registered callback by calling this function and setting the callback member in the `cbs` structure to NULL.
*
* @param[in] timer Timer handle created by `gptimer_new_timer()`
* @param[in] cbs Group of callback functions

View File

@@ -134,6 +134,8 @@ typedef struct {
/**
* @brief Create MCPWM capture channel
*
* @note The created capture channel won't be enabled until calling `mcpwm_capture_channel_enable`
*
* @param[in] cap_timer MCPWM capture timer, allocated by `mcpwm_new_capture_timer()`, will be connected to the new capture channel
* @param[in] config MCPWM capture channel configuration
* @param[out] ret_cap_channel Returned MCPWM capture channel
@@ -157,6 +159,33 @@ esp_err_t mcpwm_new_capture_channel(mcpwm_cap_timer_handle_t cap_timer, const mc
*/
esp_err_t mcpwm_del_capture_channel(mcpwm_cap_channel_handle_t cap_channel);
/**
* @brief Enable MCPWM capture channel
*
* @note This function will transit the channel state from init to enable.
* @note This function will enable the interrupt service, if it's lazy installed in `mcpwm_capture_channel_register_event_callbacks()`.
*
* @param[in] cap_channel MCPWM capture channel handle, allocated by `mcpwm_new_capture_channel()`
* @return
* - ESP_OK: Enable MCPWM capture channel successfully
* - ESP_ERR_INVALID_ARG: Enable MCPWM capture channel failed because of invalid argument
* - ESP_ERR_INVALID_STATE: Enable MCPWM capture channel failed because the channel is already enabled
* - ESP_FAIL: Enable MCPWM capture channel failed because of other error
*/
esp_err_t mcpwm_capture_channel_enable(mcpwm_cap_channel_handle_t cap_channel);
/**
* @brief Disable MCPWM capture channel
*
* @param[in] cap_channel MCPWM capture channel handle, allocated by `mcpwm_new_capture_channel()`
* @return
* - ESP_OK: Disable MCPWM capture channel successfully
* - ESP_ERR_INVALID_ARG: Disable MCPWM capture channel failed because of invalid argument
* - ESP_ERR_INVALID_STATE: Disable MCPWM capture channel failed because the channel is not enabled yet
* - ESP_FAIL: Disable MCPWM capture channel failed because of other error
*/
esp_err_t mcpwm_capture_channel_disable(mcpwm_cap_channel_handle_t cap_channel);
/**
* @brief Group of supported MCPWM capture event callbacks
* @note The callbacks are all running under ISR environment
@@ -168,12 +197,16 @@ typedef struct {
/**
* @brief Set event callbacks for MCPWM capture channel
*
* @note The first call to this function needs to be before the call to `mcpwm_capture_channel_enable`
* @note User can deregister a previously registered callback by calling this function and setting the callback member in the `cbs` structure to NULL.
*
* @param[in] cap_channel MCPWM capture channel handle, allocated by `mcpwm_new_capture_channel()`
* @param[in] cbs Group of callback functions
* @param[in] user_data User data, which will be passed to callback functions directly
* @return
* - ESP_OK: Set event callbacks successfully
* - ESP_ERR_INVALID_ARG: Set event callbacks failed because of invalid argument
* - ESP_ERR_INVALID_STATE: Set event callbacks failed because the channel is not in init state
* - ESP_FAIL: Set event callbacks failed because of other error
*/
esp_err_t mcpwm_capture_channel_register_event_callbacks(mcpwm_cap_channel_handle_t cap_channel, const mcpwm_capture_event_callbacks_t *cbs, void *user_data);
@@ -185,6 +218,7 @@ esp_err_t mcpwm_capture_channel_register_event_callbacks(mcpwm_cap_channel_handl
* @return
* - ESP_OK: Trigger software catch successfully
* - ESP_ERR_INVALID_ARG: Trigger software catch failed because of invalid argument
* - ESP_ERR_INVALID_STATE: Trigger software catch failed because the channel is not enabled yet
* - ESP_FAIL: Trigger software catch failed because of other error
*/
esp_err_t mcpwm_capture_channel_trigger_soft_catch(mcpwm_cap_channel_handle_t cap_channel);

View File

@@ -63,6 +63,8 @@ typedef struct {
/**
* @brief Set event callbacks for MCPWM comparator
*
* @note User can deregister a previously registered callback by calling this function and setting the callback member in the `cbs` structure to NULL.
*
* @param[in] cmpr MCPWM comparator handle, allocated by `mcpwm_new_comparator()`
* @param[in] cbs Group of callback functions
* @param[in] user_data User data, which will be passed to callback functions directly

View File

@@ -97,6 +97,8 @@ typedef struct {
/**
* @brief Set event callbacks for MCPWM fault
*
* @note User can deregister a previously registered callback by calling this function and setting the callback member in the `cbs` structure to NULL.
*
* @param[in] fault MCPWM GPIO fault handle, allocated by `mcpwm_new_gpio_fault()`
* @param[in] cbs Group of callback functions
* @param[in] user_data User data, which will be passed to callback functions directly

View File

@@ -82,14 +82,14 @@ typedef struct {
/**
* @brief Set brake method for MCPWM operator
*
* @param[in] operator MCPWM operator, allocated by `mcpwm_new_operator()`
* @param[in] oper MCPWM operator, allocated by `mcpwm_new_operator()`
* @param[in] config MCPWM brake configuration
* @return
* - ESP_OK: Set trip for operator successfully
* - ESP_ERR_INVALID_ARG: Set trip for operator failed because of invalid argument
* - ESP_FAIL: Set trip for operator failed because of other error
*/
esp_err_t mcpwm_operator_set_brake_on_fault(mcpwm_oper_handle_t operator, const mcpwm_brake_config_t *config);
esp_err_t mcpwm_operator_set_brake_on_fault(mcpwm_oper_handle_t oper, const mcpwm_brake_config_t *config);
/**
* @brief Try to make the operator recover from fault
@@ -97,7 +97,7 @@ esp_err_t mcpwm_operator_set_brake_on_fault(mcpwm_oper_handle_t operator, const
* @note To recover from fault or escape from trip, you make sure the fault signal has dissappeared already.
* Otherwise the recovery can't succeed.
*
* @param[in] operator MCPWM operator, allocated by `mcpwm_new_operator()`
* @param[in] oper MCPWM operator, allocated by `mcpwm_new_operator()`
* @param[in] fault MCPWM fault handle
* @return
* - ESP_OK: Recover from fault successfully
@@ -105,7 +105,7 @@ esp_err_t mcpwm_operator_set_brake_on_fault(mcpwm_oper_handle_t operator, const
* - ESP_ERR_INVALID_STATE: Recover from fault failed because the fault source is still active
* - ESP_FAIL: Recover from fault failed because of other error
*/
esp_err_t mcpwm_operator_recover_from_fault(mcpwm_oper_handle_t operator, mcpwm_fault_handle_t fault);
esp_err_t mcpwm_operator_recover_from_fault(mcpwm_oper_handle_t oper, mcpwm_fault_handle_t fault);
/**
* @brief Group of supported MCPWM operator event callbacks
@@ -119,6 +119,8 @@ typedef struct {
/**
* @brief Set event callbacks for MCPWM operator
*
* @note User can deregister a previously registered callback by calling this function and setting the callback member in the `cbs` structure to NULL.
*
* @param[in] oper MCPWM operator handle, allocated by `mcpwm_new_operator()`
* @param[in] cbs Group of callback functions
* @param[in] user_data User data, which will be passed to callback functions directly

View File

@@ -107,6 +107,9 @@ esp_err_t mcpwm_timer_start_stop(mcpwm_timer_handle_t timer, mcpwm_timer_start_s
/**
* @brief Set event callbacks for MCPWM timer
*
* @note The first call to this function needs to be before the call to `mcpwm_timer_enable`
* @note User can deregister a previously registered callback by calling this function and setting the callback member in the `cbs` structure to NULL.
*
* @param[in] timer MCPWM timer handle, allocated by `mcpwm_new_timer()`
* @param[in] cbs Group of callback functions
* @param[in] user_data User data, which will be passed to callback functions directly

View File

@@ -81,12 +81,12 @@ typedef struct {
/**
* @brief MCPWM operator brake event callback function
*
* @param[in] operator MCPWM operator handle
* @param[in] oper MCPWM operator handle
* @param[in] edata MCPWM brake event data, fed by driver
* @param[in] user_ctx User data, set in `mcpwm_operator_register_event_callbacks()`
* @return Whether a high priority task has been waken up by this function
*/
typedef bool (*mcpwm_brake_event_cb_t)(mcpwm_oper_handle_t operator, const mcpwm_brake_event_data_t *edata, void *user_ctx);
typedef bool (*mcpwm_brake_event_cb_t)(mcpwm_oper_handle_t oper, const mcpwm_brake_event_data_t *edata, void *user_ctx);
/**
* @brief MCPWM fault event data

View File

@@ -233,7 +233,8 @@ esp_err_t pcnt_unit_get_count(pcnt_unit_handle_t unit, int *value);
* @brief Set event callbacks for PCNT unit
*
* @note User registered callbacks are expected to be runnable within ISR context
* @note This function is only allowed to be called when the unit is in the init state (i.e. before calling `pcnt_unit_enable()`)
* @note The first call to this function needs to be before the call to `pcnt_unit_enable`
* @note User can deregister a previously registered callback by calling this function and setting the callback member in the `cbs` structure to NULL.
*
* @param[in] unit PCNT unit handle created by `pcnt_new_unit()`
* @param[in] cbs Group of callback functions

View File

@@ -103,9 +103,9 @@ static bool ledc_slow_clk_calibrate(void)
s_ledc_slow_clk_8M = periph_rtc_dig_clk8m_get_freq();
#if CONFIG_IDF_TARGET_ESP32H2
/* Workaround: Calibration cannot be done for CLK8M on H2, we just use its theoretic frequency */
ESP_LOGD(LEDC_TAG, "Calibration cannot be performed, approximate CLK8M_CLK : %d Hz", s_ledc_slow_clk_8M);
ESP_LOGD(LEDC_TAG, "Calibration cannot be performed, approximate CLK8M_CLK : %"PRIu32" Hz", s_ledc_slow_clk_8M);
#else
ESP_LOGD(LEDC_TAG, "Calibrate CLK8M_CLK : %d Hz", s_ledc_slow_clk_8M);
ESP_LOGD(LEDC_TAG, "Calibrate CLK8M_CLK : %"PRIu32" Hz", s_ledc_slow_clk_8M);
#endif
return true;
}
@@ -548,7 +548,7 @@ static esp_err_t ledc_set_timer_div(ledc_mode_t speed_mode, ledc_timer_t timer_n
}
/* The following debug message makes more sense for AUTO mode. */
ESP_LOGD(LEDC_TAG, "Using clock source %d (in %s mode), divisor: 0x%x\n",
ESP_LOGD(LEDC_TAG, "Using clock source %d (in %s mode), divisor: 0x%"PRIx32,
timer_clk_src, (speed_mode == LEDC_LOW_SPEED_MODE ? "slow" : "fast"), div_param);
/* The following block configures the global clock.
@@ -587,8 +587,7 @@ static esp_err_t ledc_set_timer_div(ledc_mode_t speed_mode, ledc_timer_t timer_n
return ESP_OK;
error:
ESP_LOGE(LEDC_TAG, "requested frequency and duty resolution can not be achieved, try reducing freq_hz or duty_resolution. div_param=%d",
(uint32_t ) div_param);
ESP_LOGE(LEDC_TAG, "requested frequency and duty resolution can not be achieved, try reducing freq_hz or duty_resolution. div_param=%"PRIu32, div_param);
return ESP_FAIL;
}
@@ -603,11 +602,11 @@ esp_err_t ledc_timer_config(const ledc_timer_config_t *timer_conf)
LEDC_ARG_CHECK(!((timer_conf->clk_cfg == LEDC_USE_RTC8M_CLK) && (speed_mode != LEDC_LOW_SPEED_MODE)), "Only low speed channel support RTC8M_CLK");
periph_module_enable(PERIPH_LEDC_MODULE);
if (freq_hz == 0 || duty_resolution == 0 || duty_resolution >= LEDC_TIMER_BIT_MAX) {
ESP_LOGE(LEDC_TAG, "freq_hz=%u duty_resolution=%u", freq_hz, duty_resolution);
ESP_LOGE(LEDC_TAG, "freq_hz=%"PRIu32" duty_resolution=%"PRIu32, freq_hz, duty_resolution);
return ESP_ERR_INVALID_ARG;
}
if (timer_num > LEDC_TIMER_3) {
ESP_LOGE(LEDC_TAG, "invalid timer #%u", timer_num);
ESP_LOGE(LEDC_TAG, "invalid timer #%"PRIu32, timer_num);
return ESP_ERR_INVALID_ARG;
}
@@ -673,9 +672,8 @@ esp_err_t ledc_channel_config(const ledc_channel_config_t *ledc_conf)
portENTER_CRITICAL(&ledc_spinlock);
ledc_enable_intr_type(speed_mode, ledc_channel, intr_type);
portEXIT_CRITICAL(&ledc_spinlock);
ESP_LOGD(LEDC_TAG, "LEDC_PWM CHANNEL %1u|GPIO %02u|Duty %04u|Time %01u",
ledc_channel, gpio_num, duty, timer_select
);
ESP_LOGD(LEDC_TAG, "LEDC_PWM CHANNEL %"PRIu32"|GPIO %02u|Duty %04"PRIu32"|Time %"PRIu32,
ledc_channel, gpio_num, duty, timer_select);
/*set LEDC signal in gpio matrix*/
gpio_hal_iomux_func_sel(GPIO_PIN_MUX_REG[gpio_num], PIN_FUNC_GPIO);
gpio_set_level(gpio_num, output_invert);
@@ -1048,13 +1046,13 @@ static esp_err_t _ledc_set_fade_with_step(ledc_mode_t speed_mode, ledc_channel_t
portENTER_CRITICAL(&ledc_spinlock);
ledc_duty_config(speed_mode, channel, LEDC_VAL_NO_CHANGE, duty_cur, dir, step_num, cycle_num, scale);
portEXIT_CRITICAL(&ledc_spinlock);
ESP_LOGD(LEDC_TAG, "cur duty: %d; target: %d, step: %d, cycle: %d; scale: %d; dir: %d\n",
ESP_LOGD(LEDC_TAG, "cur duty: %"PRIu32"; target: %"PRIu32", step: %d, cycle: %d; scale: %d; dir: %d\n",
duty_cur, target_duty, step_num, cycle_num, scale, dir);
} else {
portENTER_CRITICAL(&ledc_spinlock);
ledc_duty_config(speed_mode, channel, LEDC_VAL_NO_CHANGE, target_duty, dir, 0, 1, 0);
portEXIT_CRITICAL(&ledc_spinlock);
ESP_LOGD(LEDC_TAG, "Set to target duty: %d", target_duty);
ESP_LOGD(LEDC_TAG, "Set to target duty: %"PRIu32, target_duty);
}
return ESP_OK;
}

View File

@@ -242,7 +242,6 @@ esp_err_t mcpwm_new_capture_channel(mcpwm_cap_timer_handle_t cap_timer, const mc
mcpwm_hal_context_t *hal = &group->hal;
int cap_chan_id = cap_chan->cap_chan_id;
mcpwm_ll_capture_enable_channel(hal->dev, cap_chan_id, true); // enable channel
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);
mcpwm_ll_invert_input(hal->dev, cap_chan_id, config->flags.invert_cap_signal);
@@ -262,6 +261,7 @@ esp_err_t mcpwm_new_capture_channel(mcpwm_cap_timer_handle_t cap_timer, const mc
}
cap_chan->gpio_num = config->gpio_num;
cap_chan->fsm = MCPWM_CAP_CHAN_FSM_INIT;
*ret_cap_channel = cap_chan;
ESP_LOGD(TAG, "new capture channel (%d,%d) at %p", group->group_id, cap_chan_id, cap_chan);
return ESP_OK;
@@ -275,6 +275,7 @@ err:
esp_err_t mcpwm_del_capture_channel(mcpwm_cap_channel_handle_t cap_channel)
{
ESP_RETURN_ON_FALSE(cap_channel, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
ESP_RETURN_ON_FALSE(cap_channel->fsm == MCPWM_CAP_CHAN_FSM_INIT, ESP_ERR_INVALID_STATE, TAG, "channel not in init state");
mcpwm_cap_timer_t *cap_timer = cap_channel->cap_timer;
mcpwm_group_t *group = cap_timer->group;
mcpwm_hal_context_t *hal = &group->hal;
@@ -290,14 +291,46 @@ esp_err_t mcpwm_del_capture_channel(mcpwm_cap_channel_handle_t cap_channel)
mcpwm_ll_intr_clear_status(hal->dev, MCPWM_LL_EVENT_CAPTURE(cap_chan_id));
portEXIT_CRITICAL(&group->spinlock);
// disable capture channel
mcpwm_ll_capture_enable_channel(group->hal.dev, cap_channel->cap_chan_id, false);
// recycle memory resource
ESP_RETURN_ON_ERROR(mcpwm_capture_channel_destory(cap_channel), TAG, "destory capture channel failed");
return ESP_OK;
}
esp_err_t mcpwm_capture_channel_enable(mcpwm_cap_channel_handle_t cap_channel)
{
ESP_RETURN_ON_FALSE(cap_channel, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
ESP_RETURN_ON_FALSE(cap_channel->fsm == MCPWM_CAP_CHAN_FSM_INIT, ESP_ERR_INVALID_STATE, TAG, "channel not in init state");
mcpwm_hal_context_t *hal = &cap_channel->cap_timer->group->hal;
// enable interrupt service
if (cap_channel->intr) {
ESP_RETURN_ON_ERROR(esp_intr_enable(cap_channel->intr), TAG, "enable interrupt service failed");
}
// enable channel
mcpwm_ll_capture_enable_channel(hal->dev, cap_channel->cap_chan_id, true);
cap_channel->fsm = MCPWM_CAP_CHAN_FSM_ENABLE;
return ESP_OK;
}
esp_err_t mcpwm_capture_channel_disable(mcpwm_cap_channel_handle_t cap_channel)
{
ESP_RETURN_ON_FALSE(cap_channel, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
ESP_RETURN_ON_FALSE(cap_channel->fsm == MCPWM_CAP_CHAN_FSM_ENABLE, ESP_ERR_INVALID_STATE, TAG, "channel not in enable state");
mcpwm_hal_context_t *hal = &cap_channel->cap_timer->group->hal;
// disable channel
mcpwm_ll_capture_enable_channel(hal->dev, cap_channel->cap_chan_id, false);
// disable interrupt service
if (cap_channel->intr) {
ESP_RETURN_ON_ERROR(esp_intr_disable(cap_channel->intr), TAG, "disable interrupt service failed");
}
cap_channel->fsm = MCPWM_CAP_CHAN_FSM_INIT;
return ESP_OK;
}
esp_err_t mcpwm_capture_channel_register_event_callbacks(mcpwm_cap_channel_handle_t cap_channel, const mcpwm_capture_event_callbacks_t *cbs, void *user_data)
{
ESP_RETURN_ON_FALSE(cap_channel && cbs, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
@@ -317,8 +350,8 @@ esp_err_t mcpwm_capture_channel_register_event_callbacks(mcpwm_cap_channel_handl
// lazy install interrupt service
if (!cap_channel->intr) {
// we want the interrupt servie to be enabled after allocation successfully
int isr_flags = MCPWM_INTR_ALLOC_FLAG & ~ ESP_INTR_FLAG_INTRDISABLED;
ESP_RETURN_ON_FALSE(cap_channel->fsm == MCPWM_CAP_CHAN_FSM_INIT, ESP_ERR_INVALID_STATE, TAG, "channel not in init state");
int isr_flags = MCPWM_INTR_ALLOC_FLAG;
ESP_RETURN_ON_ERROR(esp_intr_alloc_intrstatus(mcpwm_periph_signals.groups[group_id].irq_id, isr_flags,
(uint32_t)mcpwm_ll_intr_get_status_reg(hal->dev), MCPWM_LL_EVENT_CAPTURE(cap_chan_id),
mcpwm_capture_default_isr, cap_channel, &cap_channel->intr), TAG, "install interrupt service for cap channel failed");
@@ -337,6 +370,7 @@ esp_err_t mcpwm_capture_channel_register_event_callbacks(mcpwm_cap_channel_handl
esp_err_t mcpwm_capture_channel_trigger_soft_catch(mcpwm_cap_channel_handle_t cap_channel)
{
ESP_RETURN_ON_FALSE(cap_channel, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
ESP_RETURN_ON_FALSE(cap_channel->fsm == MCPWM_CAP_CHAN_FSM_ENABLE, ESP_ERR_INVALID_STATE, TAG, "channel not enabled yet");
mcpwm_cap_timer_t *cap_timer = cap_channel->cap_timer;
mcpwm_group_t *group = cap_timer->group;

View File

@@ -44,13 +44,13 @@ static esp_err_t mcpwm_comparator_register_to_operator(mcpwm_cmpr_t *cmpr, mcpwm
ESP_RETURN_ON_FALSE(cmpr_id >= 0, ESP_ERR_NOT_FOUND, TAG, "no free comparator in operator (%d,%d)", oper->group->group_id, oper->oper_id);
cmpr->cmpr_id = cmpr_id;
cmpr->operator = oper;
cmpr->oper = oper;
return ESP_OK;
}
static void mcpwm_comparator_unregister_from_operator(mcpwm_cmpr_t *cmpr)
{
mcpwm_oper_t *oper = cmpr->operator;
mcpwm_oper_t *oper = cmpr->oper;
int cmpr_id = cmpr->cmpr_id;
portENTER_CRITICAL(&oper->spinlock);
@@ -63,7 +63,7 @@ static esp_err_t mcpwm_comparator_destory(mcpwm_cmpr_t *cmpr)
if (cmpr->intr) {
ESP_RETURN_ON_ERROR(esp_intr_free(cmpr->intr), TAG, "uninstall interrupt service failed");
}
if (cmpr->operator) {
if (cmpr->oper) {
mcpwm_comparator_unregister_from_operator(cmpr);
}
free(cmpr);
@@ -105,10 +105,10 @@ err:
esp_err_t mcpwm_del_comparator(mcpwm_cmpr_handle_t cmpr)
{
ESP_RETURN_ON_FALSE(cmpr, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
mcpwm_oper_t *operator= cmpr->operator;
mcpwm_group_t *group = operator->group;
mcpwm_oper_t *oper = cmpr->oper;
mcpwm_group_t *group = oper->group;
mcpwm_hal_context_t *hal = &group->hal;
int oper_id = operator->oper_id;
int oper_id = oper->oper_id;
int cmpr_id = cmpr->cmpr_id;
portENTER_CRITICAL(&group->spinlock);
@@ -125,7 +125,7 @@ esp_err_t mcpwm_del_comparator(mcpwm_cmpr_handle_t cmpr)
esp_err_t mcpwm_comparator_set_compare_value(mcpwm_cmpr_handle_t cmpr, uint32_t cmp_ticks)
{
ESP_RETURN_ON_FALSE(cmpr, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
mcpwm_oper_t *oper = cmpr->operator;
mcpwm_oper_t *oper = cmpr->oper;
mcpwm_group_t *group = oper->group;
mcpwm_timer_t *timer = oper->timer;
ESP_RETURN_ON_FALSE(timer, ESP_ERR_INVALID_STATE, TAG, "timer and operator are not connected");
@@ -142,7 +142,7 @@ esp_err_t mcpwm_comparator_set_compare_value(mcpwm_cmpr_handle_t cmpr, uint32_t
esp_err_t mcpwm_comparator_register_event_callbacks(mcpwm_cmpr_handle_t cmpr, const mcpwm_comparator_event_callbacks_t *cbs, void *user_data)
{
ESP_RETURN_ON_FALSE(cmpr && cbs, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
mcpwm_oper_t *oper = cmpr->operator;
mcpwm_oper_t *oper = cmpr->oper;
mcpwm_group_t *group = oper->group;
mcpwm_hal_context_t *hal = &group->hal;
int group_id = group->group_id;
@@ -160,7 +160,7 @@ esp_err_t mcpwm_comparator_register_event_callbacks(mcpwm_cmpr_handle_t cmpr, co
// lazy install interrupt service
if (!cmpr->intr) {
// we want the interrupt servie to be enabled after allocation successfully
// we want the interrupt service to be enabled after allocation successfully
int isr_flags = MCPWM_INTR_ALLOC_FLAG & ~ ESP_INTR_FLAG_INTRDISABLED;
ESP_RETURN_ON_ERROR(esp_intr_alloc_intrstatus(mcpwm_periph_signals.groups[group_id].irq_id, isr_flags,
(uint32_t)mcpwm_ll_intr_get_status_reg(hal->dev), MCPWM_LL_EVENT_CMP_EQUAL(oper_id, cmpr_id),
@@ -180,7 +180,7 @@ esp_err_t mcpwm_comparator_register_event_callbacks(mcpwm_cmpr_handle_t cmpr, co
static void IRAM_ATTR mcpwm_comparator_default_isr(void *args)
{
mcpwm_cmpr_t *cmpr = (mcpwm_cmpr_t *)args;
mcpwm_oper_t *oper = cmpr->operator;
mcpwm_oper_t *oper = cmpr->oper;
mcpwm_group_t *group = oper->group;
mcpwm_hal_context_t *hal = &group->hal;
int oper_id = oper->oper_id;

View File

@@ -129,7 +129,7 @@ esp_err_t mcpwm_select_periph_clock(mcpwm_group_t *group, mcpwm_timer_clock_sour
}
mcpwm_ll_group_set_clock_prescale(group->hal.dev, MCPWM_PERIPH_CLOCK_PRE_SCALE);
group->resolution_hz = periph_src_clk_hz / MCPWM_PERIPH_CLOCK_PRE_SCALE;
ESP_LOGD(TAG, "group (%d) clock resolution:%uHz", group->group_id, group->resolution_hz);
ESP_LOGD(TAG, "group (%d) clock resolution:%"PRIu32"Hz", group->group_id, group->resolution_hz);
}
return ret;
}

View File

@@ -196,18 +196,18 @@ esp_err_t mcpwm_soft_fault_activate(mcpwm_fault_handle_t fault)
ESP_RETURN_ON_FALSE(fault->type == MCPWM_FAULT_TYPE_SOFT, ESP_ERR_INVALID_ARG, TAG, "not a valid soft fault");
mcpwm_group_t *group = fault->group;
mcpwm_soft_fault_t *soft_fault = __containerof(fault, mcpwm_soft_fault_t, base);
mcpwm_oper_t *operator = soft_fault->operator;
ESP_RETURN_ON_FALSE(operator, ESP_ERR_INVALID_STATE, TAG, "no operator is assigned to the fault");
mcpwm_oper_t *oper = soft_fault->oper;
ESP_RETURN_ON_FALSE(oper, ESP_ERR_INVALID_STATE, TAG, "no operator is assigned to the fault");
switch (operator->brake_mode_on_soft_fault) {
switch (oper->brake_mode_on_soft_fault) {
case MCPWM_OPER_BRAKE_MODE_CBC:
mcpwm_ll_brake_trigger_soft_cbc(group->hal.dev, operator->oper_id);
mcpwm_ll_brake_trigger_soft_cbc(group->hal.dev, oper->oper_id);
break;
case MCPWM_OPER_BRAKE_MODE_OST:
mcpwm_ll_brake_trigger_soft_ost(group->hal.dev, operator->oper_id);
mcpwm_ll_brake_trigger_soft_ost(group->hal.dev, oper->oper_id);
break;
default:
ESP_RETURN_ON_FALSE(false, ESP_ERR_INVALID_STATE, TAG, "unknown brake mode:%d", operator->brake_mode_on_soft_fault);
ESP_RETURN_ON_FALSE(false, ESP_ERR_INVALID_STATE, TAG, "unknown brake mode:%d", oper->brake_mode_on_soft_fault);
break;
}
return ESP_OK;
@@ -243,7 +243,7 @@ esp_err_t mcpwm_fault_register_event_callbacks(mcpwm_fault_handle_t fault, const
// lazy install interrupt service
if (!gpio_fault->intr) {
// we want the interrupt servie to be enabled after allocation successfully
// we want the interrupt service to be enabled after allocation successfully
int isr_flags = MCPWM_INTR_ALLOC_FLAG & ~ESP_INTR_FLAG_INTRDISABLED;
ESP_RETURN_ON_ERROR(esp_intr_alloc_intrstatus(mcpwm_periph_signals.groups[group_id].irq_id, isr_flags,
(uint32_t)mcpwm_ll_intr_get_status_reg(hal->dev), MCPWM_LL_EVENT_FAULT_MASK(fault_id),

View File

@@ -42,13 +42,13 @@ static esp_err_t mcpwm_generator_register_to_operator(mcpwm_gen_t *gen, mcpwm_op
ESP_RETURN_ON_FALSE(gen_id >= 0, ESP_ERR_NOT_FOUND, TAG, "no free generator in operator (%d,%d)", oper->group->group_id, oper->oper_id);
gen->gen_id = gen_id;
gen->operator = oper;
gen->oper = oper;
return ESP_OK;
}
static void mcpwm_generator_unregister_from_operator(mcpwm_gen_t *gen)
{
mcpwm_oper_t *oper = gen->operator;
mcpwm_oper_t *oper = gen->oper;
int gen_id = gen->gen_id;
portENTER_CRITICAL(&oper->spinlock);
@@ -58,7 +58,7 @@ static void mcpwm_generator_unregister_from_operator(mcpwm_gen_t *gen)
static esp_err_t mcpwm_generator_destory(mcpwm_gen_t *gen)
{
if (gen->operator) {
if (gen->oper) {
mcpwm_generator_unregister_from_operator(gen);
}
free(gen);
@@ -113,7 +113,7 @@ err:
esp_err_t mcpwm_del_generator(mcpwm_gen_handle_t gen)
{
ESP_RETURN_ON_FALSE(gen, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
mcpwm_oper_t *oper = gen->operator;
mcpwm_oper_t *oper = gen->oper;
mcpwm_group_t *group = oper->group;
ESP_LOGD(TAG, "del generator (%d,%d,%d)", group->group_id, oper->oper_id, gen->gen_id);
@@ -125,7 +125,7 @@ esp_err_t mcpwm_del_generator(mcpwm_gen_handle_t gen)
esp_err_t mcpwm_generator_set_force_level(mcpwm_gen_handle_t gen, int level, bool hold_on)
{
ESP_RETURN_ON_FALSE(gen && level <= 1, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
mcpwm_oper_t *oper = gen->operator;
mcpwm_oper_t *oper = gen->oper;
mcpwm_group_t *group = oper->group;
mcpwm_hal_context_t *hal = &group->hal;
int oper_id = oper->oper_id;
@@ -151,9 +151,9 @@ esp_err_t mcpwm_generator_set_force_level(mcpwm_gen_handle_t gen, int level, boo
esp_err_t mcpwm_generator_set_actions_on_timer_event(mcpwm_gen_handle_t gen, mcpwm_gen_timer_event_action_t ev_act, ...)
{
ESP_RETURN_ON_FALSE(gen, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
mcpwm_oper_t *operator= gen->operator;
mcpwm_group_t *group = operator->group;
mcpwm_timer_t *timer = operator->timer;
mcpwm_oper_t *oper = gen->oper;
mcpwm_group_t *group = oper->group;
mcpwm_timer_t *timer = oper->timer;
ESP_RETURN_ON_FALSE(timer, ESP_ERR_INVALID_STATE, TAG, "no timer is connected to the operator");
mcpwm_gen_timer_event_action_t ev_act_itor = ev_act;
bool invalid_utep = false;
@@ -171,7 +171,7 @@ esp_err_t mcpwm_generator_set_actions_on_timer_event(mcpwm_gen_handle_t gen, mcp
va_end(it);
ESP_RETURN_ON_FALSE(false, ESP_ERR_INVALID_ARG, TAG, "UTEP and DTEZ can't be reached under MCPWM_TIMER_COUNT_MODE_UP_DOWN mode");
}
mcpwm_ll_generator_set_action_on_timer_event(group->hal.dev, operator->oper_id, gen->gen_id,
mcpwm_ll_generator_set_action_on_timer_event(group->hal.dev, oper->oper_id, gen->gen_id,
ev_act_itor.direction, ev_act_itor.event, ev_act_itor.action);
ev_act_itor = va_arg(it, mcpwm_gen_timer_event_action_t);
}
@@ -182,13 +182,13 @@ esp_err_t mcpwm_generator_set_actions_on_timer_event(mcpwm_gen_handle_t gen, mcp
esp_err_t mcpwm_generator_set_actions_on_compare_event(mcpwm_gen_handle_t gen, mcpwm_gen_compare_event_action_t ev_act, ...)
{
ESP_RETURN_ON_FALSE(gen, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
mcpwm_oper_t *operator= gen->operator;
mcpwm_group_t *group = operator->group;
mcpwm_oper_t *oper = gen->oper;
mcpwm_group_t *group = oper->group;
mcpwm_gen_compare_event_action_t ev_act_itor = ev_act;
va_list it;
va_start(it, ev_act);
while (ev_act_itor.comparator) {
mcpwm_ll_generator_set_action_on_compare_event(group->hal.dev, operator->oper_id, gen->gen_id,
mcpwm_ll_generator_set_action_on_compare_event(group->hal.dev, oper->oper_id, gen->gen_id,
ev_act_itor.direction, ev_act_itor.comparator->cmpr_id, ev_act_itor.action);
ev_act_itor = va_arg(it, mcpwm_gen_compare_event_action_t);
}
@@ -199,13 +199,13 @@ esp_err_t mcpwm_generator_set_actions_on_compare_event(mcpwm_gen_handle_t gen, m
esp_err_t mcpwm_generator_set_actions_on_brake_event(mcpwm_gen_handle_t gen, mcpwm_gen_brake_event_action_t ev_act, ...)
{
ESP_RETURN_ON_FALSE(gen, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
mcpwm_oper_t *operator= gen->operator;
mcpwm_group_t *group = operator->group;
mcpwm_oper_t *oper = gen->oper;
mcpwm_group_t *group = oper->group;
mcpwm_gen_brake_event_action_t ev_act_itor = ev_act;
va_list it;
va_start(it, ev_act);
while (ev_act_itor.brake_mode != MCPWM_OPER_BRAKE_MODE_INVALID) {
mcpwm_ll_generator_set_action_on_brake_event(group->hal.dev, operator->oper_id, gen->gen_id,
mcpwm_ll_generator_set_action_on_brake_event(group->hal.dev, oper->oper_id, gen->gen_id,
ev_act_itor.direction, ev_act_itor.brake_mode, ev_act_itor.action);
ev_act_itor = va_arg(it, mcpwm_gen_brake_event_action_t);
}
@@ -216,13 +216,13 @@ esp_err_t mcpwm_generator_set_actions_on_brake_event(mcpwm_gen_handle_t gen, mcp
esp_err_t mcpwm_generator_set_dead_time(mcpwm_gen_handle_t in_generator, mcpwm_gen_handle_t out_generator, const mcpwm_dead_time_config_t *config)
{
ESP_RETURN_ON_FALSE(in_generator && out_generator && config, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
ESP_RETURN_ON_FALSE(in_generator->operator == out_generator->operator, ESP_ERR_INVALID_ARG, TAG, "in/out generator are not derived from the same operator");
ESP_RETURN_ON_FALSE(in_generator->oper == out_generator->oper, ESP_ERR_INVALID_ARG, TAG, "in/out generator are not derived from the same operator");
ESP_RETURN_ON_FALSE(config->negedge_delay_ticks < MCPWM_LL_MAX_DEAD_DELAY && config->posedge_delay_ticks < MCPWM_LL_MAX_DEAD_DELAY,
ESP_ERR_INVALID_ARG, TAG, "delay time out of range");
mcpwm_oper_t *operator= in_generator->operator;
mcpwm_group_t *group = operator->group;
mcpwm_oper_t *oper = in_generator->oper;
mcpwm_group_t *group = oper->group;
mcpwm_hal_context_t *hal = &group->hal;
int oper_id = operator->oper_id;
int oper_id = oper->oper_id;
// Note: to better understand the following code, you should read the deadtime module topology diagram in the TRM
// check if we want to bypass the deadtime module
@@ -258,7 +258,7 @@ esp_err_t mcpwm_generator_set_dead_time(mcpwm_gen_handle_t in_generator, mcpwm_g
mcpwm_ll_deadtime_set_falling_delay(hal->dev, oper_id, config->negedge_delay_ticks);
}
ESP_LOGD(TAG, "operator (%d,%d) dead time (R:%u,F:%u), topology code:%x", group->group_id, oper_id,
ESP_LOGD(TAG, "operator (%d,%d) dead time (R:%"PRIu32",F:%"PRIu32"), topology code:%"PRIx32, group->group_id, oper_id,
config->posedge_delay_ticks, config->negedge_delay_ticks, mcpwm_ll_deadtime_get_switch_topology(hal->dev, oper_id));
return ESP_OK;
}

View File

@@ -86,19 +86,19 @@ esp_err_t mcpwm_new_operator(const mcpwm_operator_config_t *config, mcpwm_oper_h
esp_log_level_set(TAG, ESP_LOG_DEBUG);
#endif
esp_err_t ret = ESP_OK;
mcpwm_oper_t *operator= NULL;
mcpwm_oper_t *oper = NULL;
ESP_GOTO_ON_FALSE(config && ret_oper, ESP_ERR_INVALID_ARG, err, TAG, "invalid argument");
ESP_GOTO_ON_FALSE(config->group_id < SOC_MCPWM_GROUPS && config->group_id >= 0, ESP_ERR_INVALID_ARG,
err, TAG, "invalid group ID:%d", config->group_id);
operator= heap_caps_calloc(1, sizeof(mcpwm_oper_t), MCPWM_MEM_ALLOC_CAPS);
ESP_GOTO_ON_FALSE(operator, ESP_ERR_NO_MEM, err, TAG, "no mem for operator");
oper = heap_caps_calloc(1, sizeof(mcpwm_oper_t), MCPWM_MEM_ALLOC_CAPS);
ESP_GOTO_ON_FALSE(oper, ESP_ERR_NO_MEM, err, TAG, "no mem for operator");
ESP_GOTO_ON_ERROR(mcpwm_operator_register_to_group(operator, config->group_id), err, TAG, "register operator failed");
mcpwm_group_t *group = operator->group;
ESP_GOTO_ON_ERROR(mcpwm_operator_register_to_group(oper, config->group_id), err, TAG, "register operator failed");
mcpwm_group_t *group = oper->group;
int group_id = group->group_id;
mcpwm_hal_context_t *hal = &group->hal;
int oper_id = operator->oper_id;
int oper_id = oper->oper_id;
// reset MCPWM operator
mcpwm_hal_operator_reset(hal, oper_id);
@@ -113,17 +113,17 @@ esp_err_t mcpwm_new_operator(const mcpwm_operator_config_t *config, mcpwm_oper_h
mcpwm_ll_deadtime_enable_update_delay_on_sync(hal->dev, oper_id, config->flags.update_dead_time_on_sync);
// set the clock source for dead time submodule, the resolution is the same to the MCPWM group
mcpwm_ll_operator_set_deadtime_clock_src(hal->dev, oper_id, MCPWM_LL_DEADTIME_CLK_SRC_GROUP);
operator->deadtime_resolution_hz = group->resolution_hz;
oper->deadtime_resolution_hz = group->resolution_hz;
// fill in other operator members
operator->spinlock = (portMUX_TYPE)portMUX_INITIALIZER_UNLOCKED;
*ret_oper = operator;
ESP_LOGD(TAG, "new operator (%d,%d) at %p", group_id, oper_id, operator);
oper->spinlock = (portMUX_TYPE)portMUX_INITIALIZER_UNLOCKED;
*ret_oper = oper;
ESP_LOGD(TAG, "new operator (%d,%d) at %p", group_id, oper_id, oper);
return ESP_OK;
err:
if (operator) {
mcpwm_operator_destory(operator);
if (oper) {
mcpwm_operator_destory(oper);
}
return ret;
}
@@ -203,7 +203,7 @@ esp_err_t mcpwm_operator_apply_carrier(mcpwm_oper_handle_t oper, const mcpwm_car
mcpwm_ll_carrier_enable(hal->dev, oper_id, real_frequency > 0);
if (real_frequency > 0) {
ESP_LOGD(TAG, "enable carrier modulation for operator(%d,%d), freq=%uHz, duty=%.2f, FPD=%dus",
ESP_LOGD(TAG, "enable carrier modulation for operator(%d,%d), freq=%"PRIu32"Hz, duty=%.2f, FPD=%"PRIu32"us",
group->group_id, oper_id, real_frequency, real_duty, real_fpd);
} else {
ESP_LOGD(TAG, "disable carrier for operator (%d,%d)", group->group_id, oper_id);
@@ -233,7 +233,7 @@ esp_err_t mcpwm_operator_register_event_callbacks(mcpwm_oper_handle_t oper, cons
// lazy install interrupt service
if (!oper->intr) {
// we want the interrupt servie to be enabled after allocation successfully
// we want the interrupt service to be enabled after allocation successfully
int isr_flags = MCPWM_INTR_ALLOC_FLAG & ~ ESP_INTR_FLAG_INTRDISABLED;
ESP_RETURN_ON_ERROR(esp_intr_alloc_intrstatus(mcpwm_periph_signals.groups[group_id].irq_id, isr_flags,
(uint32_t)mcpwm_ll_intr_get_status_reg(hal->dev), MCPWM_LL_EVENT_OPER_MASK(oper_id),
@@ -253,13 +253,13 @@ esp_err_t mcpwm_operator_register_event_callbacks(mcpwm_oper_handle_t oper, cons
return ESP_OK;
}
esp_err_t mcpwm_operator_set_brake_on_fault(mcpwm_oper_handle_t operator, const mcpwm_brake_config_t *config)
esp_err_t mcpwm_operator_set_brake_on_fault(mcpwm_oper_handle_t oper, const mcpwm_brake_config_t *config)
{
ESP_RETURN_ON_FALSE(operator && config, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
mcpwm_group_t *group = operator->group;
ESP_RETURN_ON_FALSE(oper && config, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
mcpwm_group_t *group = oper->group;
mcpwm_fault_t *fault = config->fault;
int oper_id = operator->oper_id;
int oper_id = oper->oper_id;
mcpwm_ll_brake_enable_cbc_refresh_on_tez(group->hal.dev, oper_id, config->flags.cbc_recover_on_tez);
mcpwm_ll_fault_enable_cbc_refresh_on_tep(group->hal.dev, oper_id, config->flags.cbc_recover_on_tep);
@@ -269,17 +269,17 @@ esp_err_t mcpwm_operator_set_brake_on_fault(mcpwm_oper_handle_t operator, const
mcpwm_gpio_fault_t *gpio_fault = __containerof(fault, mcpwm_gpio_fault_t, base);
mcpwm_ll_brake_enable_cbc_mode(group->hal.dev, oper_id, gpio_fault->fault_id, config->brake_mode == MCPWM_OPER_BRAKE_MODE_CBC);
mcpwm_ll_brake_enable_oneshot_mode(group->hal.dev, oper_id, gpio_fault->fault_id, config->brake_mode == MCPWM_OPER_BRAKE_MODE_OST);
operator->brake_mode_on_gpio_fault[gpio_fault->fault_id] = config->brake_mode;
oper->brake_mode_on_gpio_fault[gpio_fault->fault_id] = config->brake_mode;
break;
}
case MCPWM_FAULT_TYPE_SOFT: {
mcpwm_soft_fault_t *soft_fault = __containerof(fault, mcpwm_soft_fault_t, base);
ESP_RETURN_ON_FALSE(!soft_fault->operator || soft_fault->operator == operator, ESP_ERR_INVALID_STATE, TAG, "soft fault already used by another operator");
soft_fault->operator = operator;
soft_fault->base.group = operator->group;
ESP_RETURN_ON_FALSE(!soft_fault->oper || soft_fault->oper == oper, ESP_ERR_INVALID_STATE, TAG, "soft fault already used by another operator");
soft_fault->oper = oper;
soft_fault->base.group = oper->group;
mcpwm_ll_brake_enable_soft_cbc(group->hal.dev, oper_id, config->brake_mode == MCPWM_OPER_BRAKE_MODE_CBC);
mcpwm_ll_brake_enable_soft_ost(group->hal.dev, oper_id, config->brake_mode == MCPWM_OPER_BRAKE_MODE_OST);
operator->brake_mode_on_soft_fault = config->brake_mode;
oper->brake_mode_on_soft_fault = config->brake_mode;
break;
}
default:
@@ -289,21 +289,21 @@ esp_err_t mcpwm_operator_set_brake_on_fault(mcpwm_oper_handle_t operator, const
return ESP_OK;
}
esp_err_t mcpwm_operator_recover_from_fault(mcpwm_oper_handle_t operator, mcpwm_fault_handle_t fault)
esp_err_t mcpwm_operator_recover_from_fault(mcpwm_oper_handle_t oper, mcpwm_fault_handle_t fault)
{
ESP_RETURN_ON_FALSE(operator && fault, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
mcpwm_group_t *group = operator->group;
ESP_RETURN_ON_FALSE(oper && fault, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
mcpwm_group_t *group = oper->group;
mcpwm_operator_brake_mode_t brake_mode;
// check the brake mode on the fault event
switch (fault->type) {
case MCPWM_FAULT_TYPE_GPIO: {
mcpwm_gpio_fault_t *gpio_fault = __containerof(fault, mcpwm_gpio_fault_t, base);
brake_mode = operator->brake_mode_on_gpio_fault[gpio_fault->fault_id];
brake_mode = oper->brake_mode_on_gpio_fault[gpio_fault->fault_id];
break;
}
case MCPWM_FAULT_TYPE_SOFT:
brake_mode = operator->brake_mode_on_soft_fault;
brake_mode = oper->brake_mode_on_soft_fault;
break;
default:
ESP_RETURN_ON_FALSE(false, ESP_ERR_INVALID_ARG, TAG, "unknown fault type:%d", fault->type);
@@ -312,13 +312,13 @@ esp_err_t mcpwm_operator_recover_from_fault(mcpwm_oper_handle_t operator, mcpwm_
bool fault_signal_is_active = false;
if (brake_mode == MCPWM_OPER_BRAKE_MODE_OST) {
fault_signal_is_active = mcpwm_ll_ost_brake_active(group->hal.dev, operator->oper_id);
fault_signal_is_active = mcpwm_ll_ost_brake_active(group->hal.dev, oper->oper_id);
// OST brake can't recover automatically, need to manually recovery the operator
if (!fault_signal_is_active) {
mcpwm_ll_brake_clear_ost(group->hal.dev, operator->oper_id);
mcpwm_ll_brake_clear_ost(group->hal.dev, oper->oper_id);
}
} else {
fault_signal_is_active = mcpwm_ll_cbc_brake_active(group->hal.dev, operator->oper_id);
fault_signal_is_active = mcpwm_ll_cbc_brake_active(group->hal.dev, oper->oper_id);
// CBC brake can recover automatically after deactivating the fault signal
}

View File

@@ -29,9 +29,9 @@ extern "C" {
#endif
#if CONFIG_MCPWM_ISR_IRAM_SAFE
#define MCPWM_INTR_ALLOC_FLAG (ESP_INTR_FLAG_SHARED | ESP_INTR_FLAG_INTRDISABLED | ESP_INTR_FLAG_IRAM)
#define MCPWM_INTR_ALLOC_FLAG (ESP_INTR_FLAG_LOWMED | ESP_INTR_FLAG_SHARED | ESP_INTR_FLAG_INTRDISABLED | ESP_INTR_FLAG_IRAM)
#else
#define MCPWM_INTR_ALLOC_FLAG (ESP_INTR_FLAG_SHARED | ESP_INTR_FLAG_INTRDISABLED)
#define MCPWM_INTR_ALLOC_FLAG (ESP_INTR_FLAG_LOWMED | ESP_INTR_FLAG_SHARED | ESP_INTR_FLAG_INTRDISABLED)
#endif
#define MCPWM_PERIPH_CLOCK_PRE_SCALE (2)
@@ -109,7 +109,7 @@ struct mcpwm_oper_t {
struct mcpwm_cmpr_t {
int cmpr_id; // comparator ID, index from 0
mcpwm_oper_t *operator; // which operator that the comparator resides in
mcpwm_oper_t *oper; // which operator that the comparator resides in
intr_handle_t intr; // interrupt handle
portMUX_TYPE spinlock; // spin lock
uint32_t compare_ticks; // compare value of this comparator
@@ -119,7 +119,7 @@ struct mcpwm_cmpr_t {
struct mcpwm_gen_t {
int gen_id; // generator ID, index from 0
mcpwm_oper_t *operator; // which operator that the generator resides in
mcpwm_oper_t *oper; // which operator that the generator resides in
int gen_gpio_num; // GPIO number used by the generator
portMUX_TYPE spinlock; // spin lock
};
@@ -138,7 +138,7 @@ struct mcpwm_fault_t {
struct mcpwm_gpio_fault_t {
mcpwm_fault_t base; // base class
int fault_id; // fault detector ID, index from 0
int gpio_num; // GPIO number of fault detector
int gpio_num; // GPIO number of fault detector
intr_handle_t intr; // interrupt handle
mcpwm_fault_event_cb_t on_fault_enter; // ISR callback function that would be invoked when fault signal got triggered
mcpwm_fault_event_cb_t on_fault_exit; // ISR callback function that would be invoked when fault signal got clear
@@ -147,7 +147,7 @@ struct mcpwm_gpio_fault_t {
struct mcpwm_soft_fault_t {
mcpwm_fault_t base; // base class
mcpwm_oper_t *operator; // the operator where the soft fault allocated from
mcpwm_oper_t *oper; // the operator where the soft fault allocated from
};
typedef enum {
@@ -193,6 +193,11 @@ typedef enum {
MCPWM_CAP_TIMER_FSM_ENABLE,
} mcpwm_cap_timer_fsm_t;
typedef enum {
MCPWM_CAP_CHAN_FSM_INIT,
MCPWM_CAP_CHAN_FSM_ENABLE,
} mcpwm_cap_channel_fsm_t;
struct mcpwm_cap_timer_t {
mcpwm_group_t *group; // which group the capture timer belongs to
portMUX_TYPE spinlock; // spin lock, to prevent concurrently accessing capture timer level resources, including registers
@@ -206,7 +211,8 @@ struct mcpwm_cap_channel_t {
int cap_chan_id; // capture channel ID, index from 0
mcpwm_cap_timer_t *cap_timer; // which capture timer that the channel resides in
uint32_t prescale; // prescale of capture signal
int gpio_num; // GPIO number used by the channel
int gpio_num; // GPIO number used by the channel
mcpwm_cap_channel_fsm_t fsm; // driver FSM
intr_handle_t intr; // Interrupt handle
mcpwm_capture_event_cb_t on_cap; // Callback function which would be invoked in capture interrupt routine
void *user_data; // user data which would be passed to the capture callback

View File

@@ -109,7 +109,7 @@ esp_err_t mcpwm_new_timer(const mcpwm_timer_config_t *config, mcpwm_timer_handle
mcpwm_ll_timer_set_clock_prescale(hal->dev, timer_id, prescale);
timer->resolution_hz = group->resolution_hz / prescale;
if (timer->resolution_hz != config->resolution_hz) {
ESP_LOGW(TAG, "adjust timer resolution to %uHz", timer->resolution_hz);
ESP_LOGW(TAG, "adjust timer resolution to %"PRIu32"Hz", timer->resolution_hz);
}
// set the peak tickes that the timer can reach to
@@ -130,7 +130,7 @@ esp_err_t mcpwm_new_timer(const mcpwm_timer_config_t *config, mcpwm_timer_handle
timer->spinlock = (portMUX_TYPE)portMUX_INITIALIZER_UNLOCKED;
timer->fsm = MCPWM_TIMER_FSM_INIT;
*ret_timer = timer;
ESP_LOGD(TAG, "new timer(%d,%d) at %p, resolution:%uHz, peak:%u, count_mod:%c",
ESP_LOGD(TAG, "new timer(%d,%d) at %p, resolution:%"PRIu32"Hz, peak:%"PRIu32", count_mod:%c",
group_id, timer_id, timer, timer->resolution_hz, timer->peak_ticks, "SUDB"[timer->count_mode]);
return ESP_OK;
@@ -166,7 +166,6 @@ esp_err_t mcpwm_del_timer(mcpwm_timer_handle_t timer)
esp_err_t mcpwm_timer_register_event_callbacks(mcpwm_timer_handle_t timer, const mcpwm_timer_event_callbacks_t *cbs, void *user_data)
{
ESP_RETURN_ON_FALSE(timer && cbs, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
ESP_RETURN_ON_FALSE(timer->fsm == MCPWM_TIMER_FSM_INIT, ESP_ERR_INVALID_STATE, TAG, "timer not in init state");
mcpwm_group_t *group = timer->group;
int group_id = group->group_id;
int timer_id = timer->timer_id;
@@ -189,6 +188,7 @@ esp_err_t mcpwm_timer_register_event_callbacks(mcpwm_timer_handle_t timer, const
// lazy install interrupt service
if (!timer->intr) {
ESP_RETURN_ON_FALSE(timer->fsm == MCPWM_TIMER_FSM_INIT, ESP_ERR_INVALID_STATE, TAG, "timer not in init state");
int isr_flags = MCPWM_INTR_ALLOC_FLAG;
ESP_RETURN_ON_ERROR(esp_intr_alloc_intrstatus(mcpwm_periph_signals.groups[group_id].irq_id, isr_flags,
(uint32_t)mcpwm_ll_intr_get_status_reg(hal->dev), MCPWM_LL_EVENT_TIMER_MASK(timer_id),

View File

@@ -41,9 +41,9 @@
#endif
#if CONFIG_PCNT_ISR_IRAM_SAFE
#define PCNT_INTR_ALLOC_FLAGS (ESP_INTR_FLAG_IRAM | ESP_INTR_FLAG_INTRDISABLED | ESP_INTR_FLAG_SHARED)
#define PCNT_INTR_ALLOC_FLAGS (ESP_INTR_FLAG_LOWMED | ESP_INTR_FLAG_IRAM | ESP_INTR_FLAG_INTRDISABLED | ESP_INTR_FLAG_SHARED)
#else
#define PCNT_INTR_ALLOC_FLAGS (ESP_INTR_FLAG_INTRDISABLED | ESP_INTR_FLAG_SHARED)
#define PCNT_INTR_ALLOC_FLAGS (ESP_INTR_FLAG_LOWMED | ESP_INTR_FLAG_INTRDISABLED | ESP_INTR_FLAG_SHARED)
#endif
#define PCNT_PM_LOCK_NAME_LEN_MAX 16
@@ -81,7 +81,7 @@ typedef enum {
struct pcnt_unit_t {
pcnt_group_t *group; // which group the pcnt unit belongs to
portMUX_TYPE spinlock; // Spinlock, stop one unit from accessing different parts of a same register concurrently
uint32_t unit_id; // allocated unit numerical ID
int unit_id; // allocated unit numerical ID
int low_limit; // low limit value
int high_limit; // high limit value
pcnt_chan_t *channels[SOC_PCNT_CHANNELS_PER_UNIT]; // array of PCNT channels
@@ -98,7 +98,7 @@ struct pcnt_unit_t {
struct pcnt_chan_t {
pcnt_unit_t *unit; // pointer to the PCNT unit where it derives from
uint32_t channel_id; // channel ID, index from 0
int channel_id; // channel ID, index from 0
int edge_gpio_num;
int level_gpio_num;
};
@@ -283,7 +283,7 @@ esp_err_t pcnt_unit_enable(pcnt_unit_handle_t unit)
if (unit->pm_lock) {
ESP_RETURN_ON_ERROR(esp_pm_lock_acquire(unit->pm_lock), TAG, "acquire pm_lock failed");
}
// enable interupt service
// enable interrupt service
if (unit->intr) {
ESP_RETURN_ON_ERROR(esp_intr_enable(unit->intr), TAG, "enable interrupt service failed");
}
@@ -366,7 +366,6 @@ esp_err_t pcnt_unit_register_event_callbacks(pcnt_unit_handle_t unit, const pcnt
{
ESP_RETURN_ON_FALSE(unit && cbs, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
// unit event callbacks should be registered in init state
ESP_RETURN_ON_FALSE(unit->fsm == PCNT_UNIT_FSM_INIT, ESP_ERR_INVALID_STATE, TAG, "unit not in init state");
pcnt_group_t *group = unit->group;
int group_id = group->group_id;
int unit_id = unit->unit_id;
@@ -382,6 +381,7 @@ esp_err_t pcnt_unit_register_event_callbacks(pcnt_unit_handle_t unit, const pcnt
// lazy install interrupt service
if (!unit->intr) {
ESP_RETURN_ON_FALSE(unit->fsm == PCNT_UNIT_FSM_INIT, ESP_ERR_INVALID_STATE, TAG, "unit not in init state");
int isr_flags = PCNT_INTR_ALLOC_FLAGS;
ESP_RETURN_ON_ERROR(esp_intr_alloc_intrstatus(pcnt_periph_signals.groups[group_id].irq, isr_flags,
(uint32_t)pcnt_ll_get_intr_status_reg(group->hal.dev), PCNT_LL_UNIT_WATCH_EVENT(unit_id),

View File

@@ -66,7 +66,7 @@ rmt_group_t *rmt_acquire_group_handle(int group_id)
_lock_release(&s_platform.mutex);
if (new_group) {
ESP_LOGD(TAG, "new group(%d) at %p, occupy=%x", group_id, group, group->occupy_mask);
ESP_LOGD(TAG, "new group(%d) at %p, occupy=%"PRIx32, group_id, group, group->occupy_mask);
}
return group;
}
@@ -153,7 +153,7 @@ esp_err_t rmt_select_periph_clock(rmt_channel_handle_t chan, rmt_clock_source_t
// no division for group clock source, to achieve highest resolution
rmt_ll_set_group_clock_src(group->hal.regs, channel_id, clk_src, 1, 1, 0);
group->resolution_hz = periph_src_clk_hz;
ESP_LOGD(TAG, "group clock resolution:%u", group->resolution_hz);
ESP_LOGD(TAG, "group clock resolution:%"PRIu32, group->resolution_hz);
return ret;
}

View File

@@ -34,9 +34,9 @@ extern "C" {
// RMT driver object is per-channel, the interrupt source is shared between channels
#if CONFIG_RMT_ISR_IRAM_SAFE
#define RMT_INTR_ALLOC_FLAG (ESP_INTR_FLAG_SHARED | ESP_INTR_FLAG_IRAM)
#define RMT_INTR_ALLOC_FLAG (ESP_INTR_FLAG_LOWMED | ESP_INTR_FLAG_SHARED | ESP_INTR_FLAG_IRAM)
#else
#define RMT_INTR_ALLOC_FLAG ESP_INTR_FLAG_SHARED
#define RMT_INTR_ALLOC_FLAG (ESP_INTR_FLAG_LOWMED | ESP_INTR_FLAG_SHARED)
#endif
// Hopefully the channel offset won't change in other targets

View File

@@ -239,7 +239,7 @@ esp_err_t rmt_new_rx_channel(const rmt_rx_channel_config_t *config, rmt_channel_
// resolution loss due to division, calculate the real resolution
rx_channel->base.resolution_hz = group->resolution_hz / real_div;
if (rx_channel->base.resolution_hz != config->resolution_hz) {
ESP_LOGW(TAG, "channel resolution loss, real=%u", rx_channel->base.resolution_hz);
ESP_LOGW(TAG, "channel resolution loss, real=%"PRIu32, rx_channel->base.resolution_hz);
}
rmt_ll_rx_set_mem_blocks(hal->regs, channel_id, rx_channel->base.mem_block_num);
@@ -282,7 +282,7 @@ esp_err_t rmt_new_rx_channel(const rmt_rx_channel_config_t *config, rmt_channel_
rx_channel->base.disable = rmt_rx_disable;
// return general channel handle
*ret_chan = &rx_channel->base;
ESP_LOGD(TAG, "new rx channel(%d,%d) at %p, gpio=%d, res=%uHz, hw_mem_base=%p, ping_pong_size=%d",
ESP_LOGD(TAG, "new rx channel(%d,%d) at %p, gpio=%d, res=%"PRIu32"Hz, hw_mem_base=%p, ping_pong_size=%d",
group_id, channel_id, rx_channel, config->gpio_num, rx_channel->base.resolution_hz,
rx_channel->base.hw_mem_base, rx_channel->ping_pong_symbols);
return ESP_OK;
@@ -405,7 +405,7 @@ static esp_err_t rmt_rx_demodulate_carrier(rmt_channel_handle_t channel, const r
portEXIT_CRITICAL(&channel->spinlock);
if (real_frequency > 0) {
ESP_LOGD(TAG, "enable carrier demodulation for channel(%d,%d), freq=%uHz", group_id, channel_id, real_frequency);
ESP_LOGD(TAG, "enable carrier demodulation for channel(%d,%d), freq=%"PRIu32"Hz", group_id, channel_id, real_frequency);
} else {
ESP_LOGD(TAG, "disable carrier demodulation for channel(%d, %d)", group_id, channel_id);
}

View File

@@ -260,7 +260,7 @@ esp_err_t rmt_new_tx_channel(const rmt_tx_channel_config_t *config, rmt_channel_
// resolution lost due to division, calculate the real resolution
tx_channel->base.resolution_hz = group->resolution_hz / real_div;
if (tx_channel->base.resolution_hz != config->resolution_hz) {
ESP_LOGW(TAG, "channel resolution loss, real=%u", tx_channel->base.resolution_hz);
ESP_LOGW(TAG, "channel resolution loss, real=%"PRIu32, tx_channel->base.resolution_hz);
}
rmt_ll_tx_set_mem_blocks(hal->regs, channel_id, tx_channel->base.mem_block_num);
@@ -300,7 +300,7 @@ esp_err_t rmt_new_tx_channel(const rmt_tx_channel_config_t *config, rmt_channel_
tx_channel->base.disable = rmt_tx_disable;
// return general channel handle
*ret_chan = &tx_channel->base;
ESP_LOGD(TAG, "new tx channel(%d,%d) at %p, gpio=%d, res=%uHz, hw_mem_base=%p, dma_mem_base=%p, ping_pong_size=%zu, queue_depth=%zu",
ESP_LOGD(TAG, "new tx channel(%d,%d) at %p, gpio=%d, res=%"PRIu32"Hz, hw_mem_base=%p, dma_mem_base=%p, ping_pong_size=%zu, queue_depth=%zu",
group_id, channel_id, tx_channel, config->gpio_num, tx_channel->base.resolution_hz,
tx_channel->base.hw_mem_base, tx_channel->base.dma_mem_base, tx_channel->ping_pong_symbols, tx_channel->queue_size);
return ESP_OK;
@@ -380,7 +380,7 @@ esp_err_t rmt_new_sync_manager(const rmt_sync_manager_config_t *config, rmt_sync
*ret_synchro = synchro;
ESP_LOGD(TAG, "new sync manager at %p, with channel mask:%02x", synchro, synchro->channel_mask);
ESP_LOGD(TAG, "new sync manager at %p, with channel mask:%02"PRIx32, synchro, synchro->channel_mask);
return ESP_OK;
err:
@@ -797,7 +797,7 @@ static esp_err_t rmt_tx_modulate_carrier(rmt_channel_handle_t channel, const rmt
portEXIT_CRITICAL(&channel->spinlock);
if (real_frequency > 0) {
ESP_LOGD(TAG, "enable carrier modulation for channel(%d,%d), freq=%uHz", group_id, channel_id, real_frequency);
ESP_LOGD(TAG, "enable carrier modulation for channel(%d,%d), freq=%"PRIu32"Hz", group_id, channel_id, real_frequency);
} else {
ESP_LOGD(TAG, "disable carrier modulation for channel(%d,%d)", group_id, channel_id);
}

View File

@@ -247,7 +247,7 @@ esp_err_t sdm_new_channel(const sdm_config_t *config, sdm_channel_handle_t *ret_
chan->spinlock = (portMUX_TYPE)portMUX_INITIALIZER_UNLOCKED;
chan->fsm = SDM_FSM_INIT; // put the channel into init state
ESP_LOGD(TAG, "new sdm channel (%d,%d) at %p, gpio=%d, sample rate=%uHz", group_id, chan_id, chan, chan->gpio_num, chan->sample_rate_hz);
ESP_LOGD(TAG, "new sdm channel (%d,%d) at %p, gpio=%d, sample rate=%"PRIu32"Hz", group_id, chan_id, chan, chan->gpio_num, chan->sample_rate_hz);
*ret_chan = chan;
return ESP_OK;
err:

View File

@@ -270,7 +270,7 @@ esp_err_t sdmmc_host_init(void)
// Reset
sdmmc_host_reset();
ESP_LOGD(TAG, "peripheral version %x, hardware config %08x", SDMMC.verid, SDMMC.hcon);
ESP_LOGD(TAG, "peripheral version %"PRIx32", hardware config %08"PRIx32, SDMMC.verid, SDMMC.hcon);
// Clear interrupt status and set interrupt mask to known state
SDMMC.rintsts.val = 0xffffffff;

View File

@@ -239,7 +239,7 @@ static esp_err_t handle_idle_state_events(void)
evt.sdmmc_status &= ~SDMMC_INTMASK_CD;
}
if (evt.sdmmc_status != 0 || evt.dma_status != 0) {
ESP_LOGE(TAG, "handle_idle_state_events unhandled: %08x %08x",
ESP_LOGE(TAG, "handle_idle_state_events unhandled: %08"PRIx32" %08"PRIx32,
evt.sdmmc_status, evt.dma_status);
}
@@ -260,13 +260,13 @@ static esp_err_t handle_event(sdmmc_command_t* cmd, sdmmc_req_state_t* state,
}
return err;
}
ESP_LOGV(TAG, "sdmmc_handle_event: event %08x %08x, unhandled %08x %08x",
ESP_LOGV(TAG, "sdmmc_handle_event: event %08"PRIx32" %08"PRIx32", unhandled %08"PRIx32" %08"PRIx32,
event.sdmmc_status, event.dma_status,
unhandled_events->sdmmc_status, unhandled_events->dma_status);
event.sdmmc_status |= unhandled_events->sdmmc_status;
event.dma_status |= unhandled_events->dma_status;
process_events(event, cmd, state, unhandled_events);
ESP_LOGV(TAG, "sdmmc_handle_event: events unhandled: %08x %08x", unhandled_events->sdmmc_status, unhandled_events->dma_status);
ESP_LOGV(TAG, "sdmmc_handle_event: events unhandled: %08"PRIx32" %08"PRIx32, unhandled_events->sdmmc_status, unhandled_events->dma_status);
return ESP_OK;
}
@@ -347,7 +347,7 @@ static void process_command_response(uint32_t status, sdmmc_command_t* cmd)
if (cmd->data) {
sdmmc_host_dma_stop();
}
ESP_LOGD(TAG, "%s: error 0x%x (status=%08x)", __func__, err, status);
ESP_LOGD(TAG, "%s: error 0x%x (status=%08"PRIx32")", __func__, err, status);
}
}
@@ -370,7 +370,7 @@ static void process_data_status(uint32_t status, sdmmc_command_t* cmd)
if (cmd->data) {
sdmmc_host_dma_stop();
}
ESP_LOGD(TAG, "%s: error 0x%x (status=%08x)", __func__, cmd->error, status);
ESP_LOGD(TAG, "%s: error 0x%x (status=%08"PRIx32")", __func__, cmd->error, status);
}
}
@@ -391,7 +391,7 @@ static esp_err_t process_events(sdmmc_event_t evt, sdmmc_command_t* cmd,
"BUSY"
};
sdmmc_event_t orig_evt = evt;
ESP_LOGV(TAG, "%s: state=%s evt=%x dma=%x", __func__, s_state_names[*pstate],
ESP_LOGV(TAG, "%s: state=%s evt=%"PRIx32" dma=%"PRIx32, __func__, s_state_names[*pstate],
evt.sdmmc_status, evt.dma_status);
sdmmc_req_state_t next_state = *pstate;
sdmmc_req_state_t state = (sdmmc_req_state_t) -1;

View File

@@ -289,7 +289,7 @@ esp_err_t sdspi_host_set_card_clk(sdspi_dev_handle_t handle, uint32_t freq_khz)
if (slot == NULL) {
return ESP_ERR_INVALID_ARG;
}
ESP_LOGD(TAG, "Setting card clock to %d kHz", freq_khz);
ESP_LOGD(TAG, "Setting card clock to %"PRIu32" kHz", freq_khz);
return configure_spi_dev(slot, freq_khz * 1000);
}
@@ -434,7 +434,7 @@ esp_err_t sdspi_host_start_command(sdspi_dev_handle_t handle, sdspi_hw_cmd_t *cm
uint32_t cmd_arg;
memcpy(&cmd_arg, cmd->arguments, sizeof(cmd_arg));
cmd_arg = __builtin_bswap32(cmd_arg);
ESP_LOGV(TAG, "%s: slot=%i, CMD%d, arg=0x%08x flags=0x%x, data=%p, data_size=%i crc=0x%02x",
ESP_LOGV(TAG, "%s: slot=%i, CMD%d, arg=0x%08"PRIx32" flags=0x%x, data=%p, data_size=%"PRIu32" crc=0x%02x",
__func__, handle, cmd_index, cmd_arg, flags, data, data_size, cmd->crc7);
spi_device_acquire_bus(slot->spi_handle, portMAX_DELAY);

View File

@@ -152,7 +152,7 @@ esp_err_t sdspi_host_do_transaction(int slot, sdmmc_command_t *cmdinfo)
// Extract response bytes and store them into cmdinfo structure
if (ret == ESP_OK) {
ESP_LOGV(TAG, "r1 = 0x%02x hw_cmd.r[0]=0x%08x", hw_cmd.r1, hw_cmd.response[0]);
ESP_LOGV(TAG, "r1 = 0x%02x hw_cmd.r[0]=0x%08"PRIx32, hw_cmd.r1, hw_cmd.response[0]);
// Some errors should be reported using return code
if (flags & (SDSPI_CMD_FLAG_RSP_R1 | SDSPI_CMD_FLAG_RSP_R1B)) {
cmdinfo->response[0] = hw_cmd.r1;

View File

@@ -185,7 +185,7 @@ esp_err_t temperature_sensor_get_celsius(temperature_sensor_handle_t tsens, floa
ESP_RETURN_ON_FALSE(tsens->fsm == TEMP_SENSOR_FSM_ENABLE, ESP_ERR_INVALID_STATE, TAG, "tsens not enabled yet");
uint32_t tsens_out = temperature_sensor_ll_get_raw_value();
ESP_LOGV(TAG, "tsens_out %d", tsens_out);
ESP_LOGV(TAG, "tsens_out %"PRIu32, tsens_out);
*out_celsius = parse_temp_sensor_raw_value(tsens_out, tsens->tsens_attribute->offset);
if (*out_celsius < tsens->tsens_attribute->range_min || *out_celsius > tsens->tsens_attribute->range_max) {

View File

@@ -1,6 +1,9 @@
set(srcs "test_app_main.c"
"test_gptimer.c"
"test_gptimer_iram.c")
"test_gptimer.c")
if(CONFIG_GPTIMER_ISR_IRAM_SAFE)
list(APPEND srcs "test_gptimer_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

View File

@@ -5,102 +5,58 @@
*/
#include <stdio.h>
#include "sdkconfig.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/semphr.h"
#include <inttypes.h>
#include "unity.h"
#include "unity_test_utils.h"
#include "esp_attr.h"
#include "driver/gptimer.h"
#include "spi_flash_mmap.h"
#include "esp_flash.h"
#include "soc/soc_caps.h"
#if CONFIG_GPTIMER_ISR_IRAM_SAFE
typedef struct {
size_t buf_size;
uint8_t *buf;
size_t flash_addr;
size_t repeat_count;
SemaphoreHandle_t done_sem;
} read_task_arg_t;
typedef struct {
size_t delay_time_us;
size_t repeat_count;
} block_task_arg_t;
static bool IRAM_ATTR on_gptimer_alarm_cb(gptimer_handle_t timer, const gptimer_alarm_event_data_t *edata, void *user_ctx)
{
block_task_arg_t *arg = (block_task_arg_t *)user_ctx;
esp_rom_delay_us(arg->delay_time_us);
arg->repeat_count++;
uint32_t *alarm_counts = (uint32_t *)user_ctx;
(*alarm_counts)++;
return false;
}
static void flash_read_task(void *varg)
static void IRAM_ATTR test_delay_post_cache_disable(void *args)
{
read_task_arg_t *arg = (read_task_arg_t *)varg;
for (size_t i = 0; i < arg->repeat_count; i++) {
TEST_ESP_OK(esp_flash_read(NULL, arg->buf, arg->flash_addr, arg->buf_size));
}
xSemaphoreGive(arg->done_sem);
vTaskDelete(NULL);
esp_rom_delay_us(1000);
}
TEST_CASE("gptimer_iram_interrupt_safe", "[gptimer]")
TEST_CASE("gptimer_interrupt_iram_safe", "[gptimer]")
{
gptimer_handle_t gptimer = NULL;
const size_t size = 128;
uint8_t *buf = malloc(size);
TEST_ASSERT_NOT_NULL(buf);
SemaphoreHandle_t done_sem = xSemaphoreCreateBinary();
TEST_ASSERT_NOT_NULL(done_sem);
read_task_arg_t read_arg = {
.buf_size = size,
.buf = buf,
.flash_addr = 0,
.repeat_count = 1000,
.done_sem = done_sem,
};
block_task_arg_t block_arg = {
.repeat_count = 0,
.delay_time_us = 100,
};
gptimer_config_t timer_config = {
.clk_src = GPTIMER_CLK_SRC_DEFAULT,
.direction = GPTIMER_COUNT_UP,
.resolution_hz = 1 * 1000 * 1000,
.resolution_hz = 1 * 1000 * 1000, // 1MHz, 1 tick = 1us
};
TEST_ESP_OK(gptimer_new_timer(&timer_config, &gptimer));
gptimer_event_callbacks_t cbs = {
.on_alarm = on_gptimer_alarm_cb,
};
uint32_t alarm_counts = 0;
TEST_ESP_OK(gptimer_register_event_callbacks(gptimer, &cbs, &alarm_counts));
gptimer_alarm_config_t alarm_config = {
.reload_count = 0,
.alarm_count = 120,
.alarm_count = 100, // 100us per alarm event
.flags.auto_reload_on_alarm = true,
};
TEST_ESP_OK(gptimer_set_alarm_action(gptimer, &alarm_config));
TEST_ESP_OK(gptimer_register_event_callbacks(gptimer, &cbs, &block_arg));
TEST_ESP_OK(gptimer_enable(gptimer));
TEST_ESP_OK(gptimer_start(gptimer));
xTaskCreatePinnedToCore(flash_read_task, "read_flash", 2048, &read_arg, 3, NULL, portNUM_PROCESSORS - 1);
// wait for task done
xSemaphoreTake(done_sem, portMAX_DELAY);
printf("alarm callback runs %d times\r\n", block_arg.repeat_count);
TEST_ASSERT_GREATER_THAN(1000, block_arg.repeat_count);
vTaskDelay(pdMS_TO_TICKS(10));
printf("disable flash cache and check the alarm events are still in working\r\n");
for (int i = 0; i < 10; i++) {
unity_utils_run_cache_disable_stub(test_delay_post_cache_disable, NULL);
}
printf("alarm counts: %"PRIu32"\r\n", alarm_counts);
TEST_ASSERT_GREATER_THAN(150, alarm_counts);
// delete gptimer
TEST_ESP_OK(gptimer_stop(gptimer));
TEST_ESP_OK(gptimer_disable(gptimer));
TEST_ESP_OK(gptimer_del_timer(gptimer));
vSemaphoreDelete(done_sem);
free(buf);
// leave time for IDLE task to recycle deleted task
vTaskDelay(2);
}
#endif // CONFIG_GPTIMER_ISR_IRAM_SAFE

View File

@@ -4,4 +4,3 @@ set(srcs "test_app_main.c"
idf_component_register(SRCS ${srcs}
WHOLE_ARCHIVE)
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

View File

@@ -6,6 +6,7 @@
#include <stdio.h>
#include <string.h>
#include <inttypes.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/queue.h"
@@ -226,7 +227,7 @@ static void i2s_read_task(void *args) {
while (task_run_flag) {
ret = i2s_channel_read(rx_handle, recv_buf, 2000, &recv_size, 300);
if (ret == ESP_ERR_TIMEOUT) {
printf("Read timeout count: %d\n", cnt++);
printf("Read timeout count: %"PRIu32"\n", cnt++);
}
}
@@ -245,7 +246,7 @@ static void i2s_write_task(void *args) {
while (task_run_flag) {
ret = i2s_channel_write(tx_handle, send_buf, 2000, &send_size, 300);
if (ret == ESP_ERR_TIMEOUT) {
printf("Write timeout count: %d\n", cnt++);
printf("Write timeout count: %"PRIu32"\n", cnt++);
}
}
@@ -607,7 +608,7 @@ TEST_CASE("I2S_memory_leak_test", "[i2s]")
TEST_ESP_OK(i2s_del_channel(rx_handle));
TEST_ASSERT(memory_left == esp_get_free_heap_size());
}
printf("\r\nHeap size after: %d\n", esp_get_free_heap_size());
printf("\r\nHeap size after: %"PRIu32"\n", esp_get_free_heap_size());
}
TEST_CASE("I2S_loopback_test", "[i2s]")
@@ -762,7 +763,7 @@ static void i2s_test_common_sample_rate(i2s_chan_handle_t rx_chan, i2s_std_clk_c
vTaskDelay(pdMS_TO_TICKS(TEST_I2S_PERIOD_MS));
TEST_ESP_OK(pcnt_unit_stop(pcnt_unit));
TEST_ESP_OK(pcnt_unit_get_count(pcnt_unit, &real_pulse));
printf("[%d Hz] %d pulses, expected %d, err %d\n", test_freq[i], real_pulse, expt_pulse, real_pulse - expt_pulse);
printf("[%"PRIu32" Hz] %d pulses, expected %d, err %d\n", test_freq[i], real_pulse, expt_pulse, real_pulse - expt_pulse);
TEST_ESP_OK(i2s_channel_disable(rx_chan));
// Check if the error between real pulse number and expected pulse number is within 1%
TEST_ASSERT_INT_WITHIN(expt_pulse * 0.01, expt_pulse, real_pulse);
@@ -858,7 +859,7 @@ TEST_CASE("I2S_package_lost_test", "[i2s]")
size_t bytes_read = 0;
int i;
for (i = 0; i < test_num; i++) {
printf("Testing %d Hz sample rate\n", test_freq[i]);
printf("Testing %"PRIu32" Hz sample rate\n", test_freq[i]);
std_cfg.clk_cfg.sample_rate_hz = test_freq[i];
std_cfg.clk_cfg.sample_rate_hz = test_freq[i];
TEST_ESP_OK(i2s_channel_reconfig_std_clock(rx_handle, &std_cfg.clk_cfg));
@@ -870,7 +871,7 @@ TEST_CASE("I2S_package_lost_test", "[i2s]")
}
TEST_ESP_OK(i2s_channel_disable(rx_handle));
if (count > 0) {
printf("package lost detected at %d Hz\n", test_freq[i]);
printf("package lost detected at %"PRIu32" Hz\n", test_freq[i]);
goto finish;
}
}

View File

@@ -3,4 +3,3 @@ set(srcs "test_app_main.c"
idf_component_register(SRCS ${srcs}
WHOLE_ARCHIVE)
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

View File

@@ -13,6 +13,7 @@
#include <stdio.h>
#include <string.h>
#include <inttypes.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/queue.h"
@@ -444,7 +445,7 @@ TEST_CASE("I2S_TDM_loopback_test_with_master_tx_and_rx", "[i2s_legacy]")
TEST_ESP_OK(i2s_driver_install(I2S_NUM_0, &master_i2s_config, 0, NULL));
TEST_ESP_OK(i2s_set_pin(I2S_NUM_0, &master_pin_config));
i2s_test_io_config(I2S_TEST_MODE_LOOPBACK);
printf("\r\nheap size: %d\n", esp_get_free_heap_size());
printf("\r\nheap size: %"PRIu32"\n", esp_get_free_heap_size());
uint8_t *data_wr = (uint8_t *)malloc(sizeof(uint8_t) * 400);
size_t i2s_bytes_write = 0;
@@ -519,7 +520,7 @@ TEST_CASE("I2S_write_and_read_test_with_master_tx_and_slave_rx", "[i2s_legacy]")
TEST_ESP_OK(i2s_driver_install(I2S_NUM_0, &master_i2s_config, 0, NULL));
TEST_ESP_OK(i2s_set_pin(I2S_NUM_0, &master_pin_config));
i2s_test_io_config(I2S_TEST_MODE_MASTER_TO_SLAVE);
printf("\r\nheap size: %d\n", esp_get_free_heap_size());
printf("\r\nheap size: %"PRIu32"\n", esp_get_free_heap_size());
i2s_config_t slave_i2s_config = {
.mode = I2S_MODE_SLAVE | I2S_MODE_RX,
@@ -551,7 +552,7 @@ TEST_CASE("I2S_write_and_read_test_with_master_tx_and_slave_rx", "[i2s_legacy]")
TEST_ESP_OK(i2s_driver_install(I2S_NUM_1, &slave_i2s_config, 0, NULL));
TEST_ESP_OK(i2s_set_pin(I2S_NUM_1, &slave_pin_config));
i2s_test_io_config(I2S_TEST_MODE_MASTER_TO_SLAVE);
printf("\r\nheap size: %d\n", esp_get_free_heap_size());
printf("\r\nheap size: %"PRIu32"\n", esp_get_free_heap_size());
uint8_t *data_wr = (uint8_t *)malloc(sizeof(uint8_t) * 400);
size_t i2s_bytes_write = 0;
@@ -623,7 +624,7 @@ TEST_CASE("I2S_write_and_read_test_master_rx_and_slave_tx", "[i2s_legacy]")
TEST_ESP_OK(i2s_driver_install(I2S_NUM_0, &master_i2s_config, 0, NULL));
TEST_ESP_OK(i2s_set_pin(I2S_NUM_0, &master_pin_config));
i2s_test_io_config(I2S_TEST_MODE_SLAVE_TO_MASTER);
printf("\r\nheap size: %d\n", esp_get_free_heap_size());
printf("\r\nheap size: %"PRIu32"\n", esp_get_free_heap_size());
i2s_config_t slave_i2s_config = {
.mode = I2S_MODE_SLAVE | I2S_MODE_TX, // Only RX
@@ -655,7 +656,7 @@ TEST_CASE("I2S_write_and_read_test_master_rx_and_slave_tx", "[i2s_legacy]")
TEST_ESP_OK(i2s_driver_install(I2S_NUM_1, &slave_i2s_config, 0, NULL));
TEST_ESP_OK(i2s_set_pin(I2S_NUM_1, &slave_pin_config));
i2s_test_io_config(I2S_TEST_MODE_SLAVE_TO_MASTER);
printf("\r\nheap size: %d\n", esp_get_free_heap_size());
printf("\r\nheap size: %"PRIu32"\n", esp_get_free_heap_size());
uint8_t *data_wr = (uint8_t *)malloc(sizeof(uint8_t) * 400);
size_t i2s_bytes_write = 0;
@@ -896,7 +897,7 @@ static void i2s_test_common_sample_rate(i2s_port_t id)
vTaskDelay(pdMS_TO_TICKS(TEST_I2S_PERIOD_MS));
TEST_ESP_OK(pcnt_unit_stop(pcnt_unit));
TEST_ESP_OK(pcnt_unit_get_count(pcnt_unit, &real_pulse));
printf("[%d Hz] %d pulses, expected %d, err %d\n", test_freq[i], real_pulse, expt_pulse, real_pulse - expt_pulse);
printf("[%"PRIu32" Hz] %d pulses, expected %d, err %d\n", test_freq[i], real_pulse, expt_pulse, real_pulse - expt_pulse);
// Check if the error between real pulse number and expected pulse number is within 1%
TEST_ASSERT_INT_WITHIN(expt_pulse * 0.01, expt_pulse, real_pulse);
}

View File

@@ -3,4 +3,3 @@ set(srcs "test_app_main.c"
idf_component_register(SRCS ${srcs}
WHOLE_ARCHIVE)
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

View File

@@ -13,8 +13,8 @@
#include "esp_log.h"
#include "esp_cpu.h"
#include "unity.h"
#include "unity_test_utils.h"
#include "esp_rom_gpio.h"
#include "ir_tools.h"
#include "driver/rmt.h"
@@ -295,7 +295,7 @@ static void do_nec_tx_rx(uint32_t flags)
// build NEC codes
cmd = 0x20;
while (cmd <= 0x30) {
ESP_LOGI(TAG, "Send command 0x%x to address 0x%x", cmd, addr);
ESP_LOGI(TAG, "Send command 0x%"PRIx32" to address 0x%"PRIx32, cmd, addr);
// Send new key code
TEST_ESP_OK(s_ir_builder->build_frame(s_ir_builder, addr, cmd));
TEST_ESP_OK(s_ir_builder->get_result(s_ir_builder, &items, &length));
@@ -315,7 +315,7 @@ static void do_nec_tx_rx(uint32_t flags)
length /= 4; // one RMT = 4 Bytes
if (s_ir_parser->input(s_ir_parser, items, length) == ESP_OK) {
if (s_ir_parser->get_scan_code(s_ir_parser, &addr, &cmd, &repeat) == ESP_OK) {
ESP_LOGI(TAG, "Scan Code %s --- addr: 0x%04x cmd: 0x%04x", repeat ? "(repeat)" : "", addr, cmd);
ESP_LOGI(TAG, "Scan Code %s --- addr: 0x%04"PRIx32" cmd: 0x%04"PRIx32, repeat ? "(repeat)" : "", addr, cmd);
}
}
vRingbufferReturnItem(rb, (void *) items);
@@ -397,7 +397,7 @@ TEST_CASE("RMT TX stop", "[rmt]")
vTaskDelay(pdMS_TO_TICKS(1000));
// build NEC codes
ESP_LOGI(TAG, "Plan to send command 0x%x~0x%x to address 0x%x", cmd, cmd + count, addr);
ESP_LOGI(TAG, "Plan to send command 0x%"PRIx32"~0x%"PRIx32" to address 0x%"PRIx32, cmd, cmd + count, addr);
for (int i = 0; i <= count; i++) {
TEST_ESP_OK(s_ir_builder->build_frame(s_ir_builder, addr, cmd));
cmd++;
@@ -417,7 +417,7 @@ TEST_CASE("RMT TX stop", "[rmt]")
length /= 4; // one RMT = 4 Bytes
if (s_ir_parser->input(s_ir_parser, frames, length) == ESP_OK) {
if (s_ir_parser->get_scan_code(s_ir_parser, &addr, &cmd, &repeat) == ESP_OK) {
ESP_LOGI(TAG, "Scan Code %s --- addr: 0x%04x cmd: 0x%04x", repeat ? "(repeat)" : "", addr, cmd);
ESP_LOGI(TAG, "Scan Code %s --- addr: 0x%04"PRIx32"cmd: 0x%04"PRIx32, repeat ? "(repeat)" : "", addr, cmd);
num++;
}
}
@@ -527,12 +527,14 @@ TEST_CASE("RMT TX simultaneously", "[rmt]")
TEST_ESP_OK(rmt_wait_tx_done(channel0, portMAX_DELAY));
TEST_ESP_OK(rmt_wait_tx_done(channel1, portMAX_DELAY));
ESP_LOGI(TAG, "tx_end_time0=%u, tx_end_time1=%u", tx_end_time0, tx_end_time1);
ESP_LOGI(TAG, "tx_end_time0=%"PRIu32", tx_end_time1=%"PRIu32, tx_end_time0, tx_end_time1);
TEST_ASSERT_LESS_OR_EQUAL_UINT32(2000, tx_end_time1 - tx_end_time0);
TEST_ESP_OK(rmt_remove_channel_from_group(channel0));
TEST_ESP_OK(rmt_remove_channel_from_group(channel1));
rmt_register_tx_end_callback(NULL, NULL);
TEST_ESP_OK(rmt_driver_uninstall(channel0));
TEST_ESP_OK(rmt_driver_uninstall(channel1));
@@ -568,7 +570,7 @@ TEST_CASE("RMT TX loop", "[rmt]")
// register callback functions, invoked when tx loop count to ceiling
rmt_register_tx_end_callback(rmt_tx_loop_end, NULL);
// build NEC codes
ESP_LOGI(TAG, "Send command 0x%x to address 0x%x", cmd, addr);
ESP_LOGI(TAG, "Send command 0x%"PRIx32" to address 0x%"PRIx32, cmd, addr);
// Send new key code
TEST_ESP_OK(s_ir_builder->build_frame(s_ir_builder, addr, cmd));
TEST_ESP_OK(s_ir_builder->get_result(s_ir_builder, &items, &length));
@@ -582,7 +584,7 @@ TEST_CASE("RMT TX loop", "[rmt]")
if (s_ir_parser->input(s_ir_parser, items, length) == ESP_OK) {
if (s_ir_parser->get_scan_code(s_ir_parser, &addr, &cmd, &repeat) == ESP_OK) {
count++;
ESP_LOGI(TAG, "Scan Code %s --- addr: 0x%04x cmd: 0x%04x", repeat ? "(repeat)" : "", addr, cmd);
ESP_LOGI(TAG, "Scan Code %s --- addr: 0x%04"PRIx32" cmd: 0x%04"PRIx32, repeat ? "(repeat)" : "", addr, cmd);
}
}
vRingbufferReturnItem(rb, (void *) items);
@@ -593,6 +595,42 @@ TEST_CASE("RMT TX loop", "[rmt]")
}
TEST_ASSERT_EQUAL(10, count);
rmt_register_tx_end_callback(NULL, NULL);
rmt_clean_testbench(tx_channel, rx_channel);
}
#endif
static void IRAM_ATTR test_delay_post_cache_disable(void *args)
{
esp_rom_delay_us(10000);
}
TEST_CASE("RMT Interrupt IRAM Safe", "[rmt]")
{
rmt_config_t tx = {
.channel = RMT_CHANNEL_0,
.gpio_num = 0,
.mem_block_num = 1,
.clk_div = 40,
.rmt_mode = RMT_MODE_TX,
};
TEST_ESP_OK(rmt_config(&tx));
TEST_ESP_OK(rmt_set_source_clk(tx.channel, RMT_BASECLK_APB));
// 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
rmt_item32_t items[256] = {};
for (int i = 0; i < 256; i++) {
items[i].level0 = 0;
items[i].duration0 = 1;
items[i].level1 = 1;
items[i].duration1 = 1;
}
rmt_write_items(RMT_CHANNEL_0, items, 256, false);
unity_utils_run_cache_disable_stub(test_delay_post_cache_disable, NULL);
TEST_ESP_OK(rmt_wait_tx_done(RMT_CHANNEL_0, portMAX_DELAY));
TEST_ESP_OK(rmt_driver_uninstall(RMT_CHANNEL_0));
}

View File

@@ -16,4 +16,3 @@ endif()
# the component can be registered as WHOLE_ARCHIVE
idf_component_register(SRCS ${srcs}
WHOLE_ARCHIVE)
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

View File

@@ -4,6 +4,7 @@
* SPDX-License-Identifier: Apache-2.0
*/
#include <stdio.h>
#include <inttypes.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/event_groups.h"
@@ -101,6 +102,9 @@ TEST_CASE("mcpwm_capture_ext_gpio", "[mcpwm]")
uint32_t cap_value[2] = {0};
TEST_ESP_OK(mcpwm_capture_channel_register_event_callbacks(pps_channel, &cbs, cap_value));
printf("enable capture channel\r\n");
TEST_ESP_OK(mcpwm_capture_channel_enable(pps_channel));
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));
@@ -110,12 +114,13 @@ TEST_CASE("mcpwm_capture_ext_gpio", "[mcpwm]")
vTaskDelay(pdMS_TO_TICKS(100));
gpio_set_level(cap_gpio, 0);
vTaskDelay(pdMS_TO_TICKS(100));
printf("capture value: Pos=%u, Neg=%u\r\n", cap_value[0], cap_value[1]);
printf("capture value: Pos=%"PRIu32", Neg=%"PRIu32"\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(100000, clk_src_res / 10, cap_value[1] - cap_value[0]);
printf("uninstall capture channel and timer\r\n");
TEST_ESP_OK(mcpwm_capture_channel_disable(pps_channel));
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));
@@ -153,12 +158,17 @@ TEST_CASE("mcpwm_capture_software_catch", "[mcpwm]")
test_soft_catch_user_data_t test_callback_data = {};
TEST_ESP_OK(mcpwm_new_capture_channel(cap_timer, &cap_chan_config, &cap_channel));
TEST_ESP_ERR(ESP_ERR_INVALID_STATE, mcpwm_capture_channel_trigger_soft_catch(cap_channel));
printf("register event callback for capture channel\r\n");
mcpwm_capture_event_callbacks_t cbs = {
.on_cap = soft_cap_callback,
};
TEST_ESP_OK(mcpwm_capture_channel_register_event_callbacks(cap_channel, &cbs, &test_callback_data));
printf("enable capture channel\r\n");
TEST_ESP_OK(mcpwm_capture_channel_enable(cap_channel));
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));
@@ -178,6 +188,7 @@ TEST_CASE("mcpwm_capture_software_catch", "[mcpwm]")
TEST_ASSERT_UINT_WITHIN(80000, clk_src_res / 100, delta);
printf("uninstall capture channel and timer\r\n");
TEST_ESP_OK(mcpwm_capture_channel_disable(cap_channel));
TEST_ESP_OK(mcpwm_capture_timer_disable(cap_timer));
TEST_ESP_OK(mcpwm_del_capture_channel(cap_channel));
TEST_ESP_OK(mcpwm_del_capture_timer(cap_timer));
@@ -210,6 +221,7 @@ TEST_CASE("mcpwm_capture_timer_sync_phase_lock", "[mcpwm]")
.sync_src = soft_sync,
};
TEST_ESP_OK(mcpwm_capture_timer_set_phase_on_sync(cap_timer, &sync_config));
mcpwm_cap_channel_handle_t cap_channel = NULL;
mcpwm_capture_channel_config_t cap_chan_config = {
.gpio_num = -1, // don't need any GPIO, we use software to trigger a catch
@@ -223,15 +235,19 @@ TEST_CASE("mcpwm_capture_timer_sync_phase_lock", "[mcpwm]")
uint32_t cap_data;
TEST_ESP_OK(mcpwm_capture_channel_register_event_callbacks(cap_channel, &cbs, &cap_data));
printf("enable capture channel\r\n");
TEST_ESP_OK(mcpwm_capture_channel_enable(cap_channel));
TEST_ESP_OK(mcpwm_capture_channel_trigger_soft_catch(cap_channel));
vTaskDelay(pdMS_TO_TICKS(10));
printf("capture data before sync: %u\r\n", cap_data);
printf("capture data before sync: %"PRIu32"\r\n", cap_data);
TEST_ESP_OK(mcpwm_soft_sync_activate(soft_sync));
TEST_ESP_OK(mcpwm_capture_channel_trigger_soft_catch(cap_channel));
vTaskDelay(pdMS_TO_TICKS(10));
printf("capture data after sync: %u\r\n", cap_data);
printf("capture data after sync: %"PRIu32"\r\n", cap_data);
TEST_ASSERT_EQUAL(1000, cap_data);
TEST_ESP_OK(mcpwm_capture_channel_disable(cap_channel));
TEST_ESP_OK(mcpwm_del_capture_channel(cap_channel));
TEST_ESP_OK(mcpwm_del_capture_timer(cap_timer));
TEST_ESP_OK(mcpwm_del_sync_src(soft_sync));

View File

@@ -3,6 +3,7 @@
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <inttypes.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "unity.h"
@@ -14,7 +15,7 @@
TEST_CASE("mcpwm_comparator_install_uninstall", "[mcpwm]")
{
mcpwm_timer_handle_t timer;
mcpwm_oper_handle_t operator;
mcpwm_oper_handle_t oper;
mcpwm_cmpr_handle_t comparators[SOC_MCPWM_COMPARATORS_PER_OPERATOR];
mcpwm_timer_config_t timer_config = {
@@ -29,25 +30,25 @@ TEST_CASE("mcpwm_comparator_install_uninstall", "[mcpwm]")
};
printf("install timer and operator");
TEST_ESP_OK(mcpwm_new_timer(&timer_config, &timer));
TEST_ESP_OK(mcpwm_new_operator(&operator_config, &operator));
TEST_ESP_OK(mcpwm_new_operator(&operator_config, &oper));
printf("install comparator\r\n");
mcpwm_comparator_config_t comparator_config = {};
for (int i = 0; i < SOC_MCPWM_COMPARATORS_PER_OPERATOR; i++) {
TEST_ESP_OK(mcpwm_new_comparator(operator, &comparator_config, &comparators[i]));
TEST_ESP_OK(mcpwm_new_comparator(oper, &comparator_config, &comparators[i]));
}
TEST_ESP_ERR(ESP_ERR_NOT_FOUND, mcpwm_new_comparator(operator, &comparator_config, &comparators[0]));
TEST_ESP_ERR(ESP_ERR_NOT_FOUND, mcpwm_new_comparator(oper, &comparator_config, &comparators[0]));
printf("connect MCPWM timer and operators\r\n");
TEST_ESP_OK(mcpwm_operator_connect_timer(operator, timer));
TEST_ESP_OK(mcpwm_operator_connect_timer(oper, timer));
printf("uninstall timer, operator and comparators\r\n");
// can't delete operator if the comparators are still in working
TEST_ESP_ERR(ESP_ERR_INVALID_STATE, mcpwm_del_operator(operator));
TEST_ESP_ERR(ESP_ERR_INVALID_STATE, mcpwm_del_operator(oper));
for (int i = 0; i < SOC_MCPWM_COMPARATORS_PER_OPERATOR; i++) {
TEST_ESP_OK(mcpwm_del_comparator(comparators[i]));
}
TEST_ESP_OK(mcpwm_del_operator(operator));
TEST_ESP_OK(mcpwm_del_operator(oper));
TEST_ESP_OK(mcpwm_del_timer(timer));
}
@@ -61,7 +62,7 @@ static bool test_compare_on_reach(mcpwm_cmpr_handle_t cmpr, const mcpwm_compare_
TEST_CASE("mcpwm_comparator_event_callback", "[mcpwm]")
{
mcpwm_timer_handle_t timer;
mcpwm_oper_handle_t operator;
mcpwm_oper_handle_t oper;
mcpwm_cmpr_handle_t comparator;
mcpwm_timer_config_t timer_config = {
@@ -75,15 +76,15 @@ TEST_CASE("mcpwm_comparator_event_callback", "[mcpwm]")
.group_id = 0,
};
mcpwm_comparator_config_t comparator_config = {};
printf("install timer, operator and comparator");
printf("install timer, operator and comparator\r\n");
TEST_ESP_OK(mcpwm_new_timer(&timer_config, &timer));
TEST_ESP_OK(mcpwm_new_operator(&operator_config, &operator));
TEST_ESP_OK(mcpwm_new_comparator(operator, &comparator_config, &comparator));
TEST_ESP_OK(mcpwm_new_operator(&operator_config, &oper));
TEST_ESP_OK(mcpwm_new_comparator(oper, &comparator_config, &comparator));
// set compare value before connecting timer and operator will fail
TEST_ESP_ERR(ESP_ERR_INVALID_STATE, mcpwm_comparator_set_compare_value(comparator, 5000));
printf("connect MCPWM timer and operators\r\n");
TEST_ESP_OK(mcpwm_operator_connect_timer(operator, timer));
TEST_ESP_OK(mcpwm_operator_connect_timer(oper, timer));
// compare ticks can't exceed the timer's period ticks
TEST_ESP_ERR(ESP_ERR_INVALID_ARG, mcpwm_comparator_set_compare_value(comparator, 20 * 1000));
TEST_ESP_OK(mcpwm_comparator_set_compare_value(comparator, 5 * 1000));
@@ -101,13 +102,13 @@ TEST_CASE("mcpwm_comparator_event_callback", "[mcpwm]")
vTaskDelay(pdMS_TO_TICKS(1000));
TEST_ESP_OK(mcpwm_timer_start_stop(timer, MCPWM_TIMER_STOP_EMPTY));
printf("compare_counts=%u\r\n", compare_counts);
printf("compare_counts=%"PRIu32"\r\n", compare_counts);
// the timer period is 10ms, the expected compare_counts = 1s/10ms = 100
TEST_ASSERT_INT_WITHIN(1, 100, compare_counts);
printf("uninstall timer, operator and comparator\r\n");
TEST_ESP_OK(mcpwm_timer_disable(timer));
TEST_ESP_OK(mcpwm_del_comparator(comparator));
TEST_ESP_OK(mcpwm_del_operator(operator));
TEST_ESP_OK(mcpwm_del_operator(oper));
TEST_ESP_OK(mcpwm_del_timer(timer));
}

View File

@@ -45,11 +45,11 @@ TEST_CASE("mcpwm_generator_force_level_hold_on", "[mcpwm]")
{
// The operator can even work without the timer
printf("create operator and generator\r\n");
mcpwm_oper_handle_t operator = NULL;
mcpwm_oper_handle_t oper = NULL;
mcpwm_operator_config_t operator_config = {
.group_id = 0,
};
TEST_ESP_OK(mcpwm_new_operator(&operator_config, &operator));
TEST_ESP_OK(mcpwm_new_operator(&operator_config, &oper));
mcpwm_gen_handle_t generator = NULL;
const int gen_gpio = 0;
@@ -57,7 +57,7 @@ TEST_CASE("mcpwm_generator_force_level_hold_on", "[mcpwm]")
.gen_gpio_num = gen_gpio,
.flags.io_loop_back = true, // loop back for test
};
TEST_ESP_OK(mcpwm_new_generator(operator, &generator_config, &generator));
TEST_ESP_OK(mcpwm_new_generator(oper, &generator_config, &generator));
printf("add force level to the generator, hold on");
for (int i = 0; i < 10; i++) {
@@ -74,7 +74,7 @@ TEST_CASE("mcpwm_generator_force_level_hold_on", "[mcpwm]")
printf("delete generator and operator\r\n");
TEST_ESP_OK(mcpwm_del_generator(generator));
TEST_ESP_OK(mcpwm_del_operator(operator));
TEST_ESP_OK(mcpwm_del_operator(oper));
}
TEST_CASE("mcpwm_generator_force_level_recovery", "[mcpwm]")
@@ -92,13 +92,13 @@ TEST_CASE("mcpwm_generator_force_level_recovery", "[mcpwm]")
TEST_ESP_OK(mcpwm_timer_enable(timer));
printf("create operator\r\n");
mcpwm_oper_handle_t operator = NULL;
mcpwm_oper_handle_t oper = NULL;
mcpwm_operator_config_t operator_config = {
.group_id = 0,
.flags.update_gen_action_on_tez = true,
};
TEST_ESP_OK(mcpwm_new_operator(&operator_config, &operator));
TEST_ESP_OK(mcpwm_operator_connect_timer(operator, timer));
TEST_ESP_OK(mcpwm_new_operator(&operator_config, &oper));
TEST_ESP_OK(mcpwm_operator_connect_timer(oper, timer));
printf("create generator\r\n");
mcpwm_gen_handle_t generator = NULL;
@@ -107,7 +107,7 @@ TEST_CASE("mcpwm_generator_force_level_recovery", "[mcpwm]")
.gen_gpio_num = gen_gpio,
.flags.io_loop_back = true, // loop back for test
};
TEST_ESP_OK(mcpwm_new_generator(operator, &generator_config, &generator));
TEST_ESP_OK(mcpwm_new_generator(oper, &generator_config, &generator));
printf("add force level to the generator, and recovery by events");
TEST_ESP_OK(mcpwm_generator_set_force_level(generator, 0, false));
@@ -142,7 +142,7 @@ TEST_CASE("mcpwm_generator_force_level_recovery", "[mcpwm]")
printf("delete generator, operator and timer\r\n");
TEST_ESP_OK(mcpwm_timer_disable(timer));
TEST_ESP_OK(mcpwm_del_generator(generator));
TEST_ESP_OK(mcpwm_del_operator(operator));
TEST_ESP_OK(mcpwm_del_operator(oper));
TEST_ESP_OK(mcpwm_del_timer(timer));
}
@@ -227,9 +227,9 @@ static void mcpwm_gen_action_test_template(uint32_t timer_resolution, uint32_t p
mcpwm_operator_config_t operator_config = {
.group_id = 0,
};
mcpwm_oper_handle_t operator = NULL;
TEST_ESP_OK(mcpwm_new_operator(&operator_config, &operator));
TEST_ESP_OK(mcpwm_operator_connect_timer(operator, timer));
mcpwm_oper_handle_t oper = NULL;
TEST_ESP_OK(mcpwm_new_operator(&operator_config, &oper));
TEST_ESP_OK(mcpwm_operator_connect_timer(oper, timer));
TEST_ESP_OK(mcpwm_timer_enable(timer));
@@ -238,8 +238,8 @@ static void mcpwm_gen_action_test_template(uint32_t timer_resolution, uint32_t p
mcpwm_comparator_config_t comparator_config = {
.flags.update_cmp_on_tez = true,
};
TEST_ESP_OK(mcpwm_new_comparator(operator, &comparator_config, &comparator_a));
TEST_ESP_OK(mcpwm_new_comparator(operator, &comparator_config, &comparator_b));
TEST_ESP_OK(mcpwm_new_comparator(oper, &comparator_config, &comparator_a));
TEST_ESP_OK(mcpwm_new_comparator(oper, &comparator_config, &comparator_b));
TEST_ESP_OK(mcpwm_comparator_set_compare_value(comparator_a, cmpa));
TEST_ESP_OK(mcpwm_comparator_set_compare_value(comparator_b, cmpb));
@@ -248,9 +248,9 @@ static void mcpwm_gen_action_test_template(uint32_t timer_resolution, uint32_t p
mcpwm_generator_config_t generator_config = {
.gen_gpio_num = gpioa,
};
TEST_ESP_OK(mcpwm_new_generator(operator, &generator_config, &generator_a));
TEST_ESP_OK(mcpwm_new_generator(oper, &generator_config, &generator_a));
generator_config.gen_gpio_num = gpiob;
TEST_ESP_OK(mcpwm_new_generator(operator, &generator_config, &generator_b));
TEST_ESP_OK(mcpwm_new_generator(oper, &generator_config, &generator_b));
set_generator_actions(generator_a, generator_b, comparator_a, comparator_b);
@@ -264,7 +264,7 @@ static void mcpwm_gen_action_test_template(uint32_t timer_resolution, uint32_t p
TEST_ESP_OK(mcpwm_del_generator(generator_b));
TEST_ESP_OK(mcpwm_del_comparator(comparator_a));
TEST_ESP_OK(mcpwm_del_comparator(comparator_b));
TEST_ESP_OK(mcpwm_del_operator(operator));
TEST_ESP_OK(mcpwm_del_operator(oper));
TEST_ESP_OK(mcpwm_del_timer(timer));
}
@@ -398,9 +398,9 @@ static void mcpwm_deadtime_test_template(uint32_t timer_resolution, uint32_t per
mcpwm_operator_config_t operator_config = {
.group_id = 0,
};
mcpwm_oper_handle_t operator = NULL;
TEST_ESP_OK(mcpwm_new_operator(&operator_config, &operator));
TEST_ESP_OK(mcpwm_operator_connect_timer(operator, timer));
mcpwm_oper_handle_t oper = NULL;
TEST_ESP_OK(mcpwm_new_operator(&operator_config, &oper));
TEST_ESP_OK(mcpwm_operator_connect_timer(oper, timer));
TEST_ESP_OK(mcpwm_timer_enable(timer));
@@ -409,8 +409,8 @@ static void mcpwm_deadtime_test_template(uint32_t timer_resolution, uint32_t per
mcpwm_comparator_config_t comparator_config = {
.flags.update_cmp_on_tez = true,
};
TEST_ESP_OK(mcpwm_new_comparator(operator, &comparator_config, &comparator_a));
TEST_ESP_OK(mcpwm_new_comparator(operator, &comparator_config, &comparator_b));
TEST_ESP_OK(mcpwm_new_comparator(oper, &comparator_config, &comparator_a));
TEST_ESP_OK(mcpwm_new_comparator(oper, &comparator_config, &comparator_b));
TEST_ESP_OK(mcpwm_comparator_set_compare_value(comparator_a, cmpa));
TEST_ESP_OK(mcpwm_comparator_set_compare_value(comparator_b, cmpb));
@@ -419,9 +419,9 @@ static void mcpwm_deadtime_test_template(uint32_t timer_resolution, uint32_t per
mcpwm_generator_config_t generator_config = {
.gen_gpio_num = gpioa,
};
TEST_ESP_OK(mcpwm_new_generator(operator, &generator_config, &generator_a));
TEST_ESP_OK(mcpwm_new_generator(oper, &generator_config, &generator_a));
generator_config.gen_gpio_num = gpiob;
TEST_ESP_OK(mcpwm_new_generator(operator, &generator_config, &generator_b));
TEST_ESP_OK(mcpwm_new_generator(oper, &generator_config, &generator_b));
set_generator_actions(generator_a, generator_b, comparator_a, comparator_b);
set_dead_time(generator_a, generator_b);
@@ -436,7 +436,7 @@ static void mcpwm_deadtime_test_template(uint32_t timer_resolution, uint32_t per
TEST_ESP_OK(mcpwm_del_generator(generator_b));
TEST_ESP_OK(mcpwm_del_comparator(comparator_a));
TEST_ESP_OK(mcpwm_del_comparator(comparator_b));
TEST_ESP_OK(mcpwm_del_operator(operator));
TEST_ESP_OK(mcpwm_del_operator(oper));
TEST_ESP_OK(mcpwm_del_timer(timer));
}

View File

@@ -4,13 +4,14 @@
* SPDX-License-Identifier: Apache-2.0
*/
#include <stdio.h>
#include <inttypes.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/event_groups.h"
#include "unity.h"
#include "unity_test_utils.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"
@@ -27,15 +28,12 @@ static bool IRAM_ATTR test_capture_callback_iram_safe(mcpwm_cap_channel_handle_t
return false;
}
static void IRAM_ATTR test_mcpwm_capture_gpio_simulate(int gpio_sig)
static void IRAM_ATTR test_simulate_input_post_cache_disable(void *args)
{
// disable flash cache
spi_flash_guard_get()->start();
int gpio_sig = (int)args;
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]")
@@ -71,19 +69,23 @@ TEST_CASE("mcpwm_capture_iram_safe", "[mcpwm]")
uint32_t cap_value[2] = {0};
TEST_ESP_OK(mcpwm_capture_channel_register_event_callbacks(pps_channel, &cbs, cap_value));
printf("enable capture channel\r\n");
TEST_ESP_OK(mcpwm_capture_channel_enable(pps_channel));
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);
unity_utils_run_cache_disable_stub(test_simulate_input_post_cache_disable, (void *)cap_gpio);
printf("capture value: Pos=%u, Neg=%u\r\n", cap_value[0], cap_value[1]);
printf("capture value: Pos=%"PRIu32", Neg=%"PRIu32"\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_capture_channel_disable(pps_channel));
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));

View File

@@ -73,15 +73,15 @@ TEST_CASE("mcpwm_operator_carrier", "[mcpwm]")
mcpwm_operator_config_t operator_config = {
.group_id = 0,
};
mcpwm_oper_handle_t operator = NULL;
TEST_ESP_OK(mcpwm_new_operator(&operator_config, &operator));
TEST_ESP_OK(mcpwm_operator_connect_timer(operator, timer));
mcpwm_oper_handle_t oper = NULL;
TEST_ESP_OK(mcpwm_new_operator(&operator_config, &oper));
TEST_ESP_OK(mcpwm_operator_connect_timer(oper, timer));
mcpwm_generator_config_t generator_config = {
.gen_gpio_num = 0,
};
mcpwm_gen_handle_t generator = NULL;
TEST_ESP_OK(mcpwm_new_generator(operator, &generator_config, &generator));
TEST_ESP_OK(mcpwm_new_generator(oper, &generator_config, &generator));
TEST_ESP_OK(mcpwm_generator_set_actions_on_timer_event(generator,
MCPWM_GEN_TIMER_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, MCPWM_TIMER_EVENT_EMPTY, MCPWM_GEN_ACTION_TOGGLE),
@@ -93,7 +93,7 @@ TEST_CASE("mcpwm_operator_carrier", "[mcpwm]")
.duty_cycle = 0.5,
.first_pulse_duration_us = 10,
};
TEST_ESP_OK(mcpwm_operator_apply_carrier(operator, &carrier_config));
TEST_ESP_OK(mcpwm_operator_apply_carrier(oper, &carrier_config));
TEST_ESP_OK(mcpwm_timer_enable(timer));
@@ -104,7 +104,7 @@ TEST_CASE("mcpwm_operator_carrier", "[mcpwm]")
printf("remove carrier from PWM wave\r\n");
carrier_config.frequency_hz = 0;
TEST_ESP_OK(mcpwm_operator_apply_carrier(operator, &carrier_config));
TEST_ESP_OK(mcpwm_operator_apply_carrier(oper, &carrier_config));
TEST_ESP_OK(mcpwm_timer_start_stop(timer, MCPWM_TIMER_START_NO_STOP));
vTaskDelay(pdMS_TO_TICKS(200));
TEST_ESP_OK(mcpwm_timer_start_stop(timer, MCPWM_TIMER_STOP_EMPTY));
@@ -112,17 +112,17 @@ TEST_CASE("mcpwm_operator_carrier", "[mcpwm]")
TEST_ESP_OK(mcpwm_timer_disable(timer));
TEST_ESP_OK(mcpwm_del_generator(generator));
TEST_ESP_OK(mcpwm_del_operator(operator));
TEST_ESP_OK(mcpwm_del_operator(oper));
TEST_ESP_OK(mcpwm_del_timer(timer));
}
static bool test_cbc_brake_on_gpio_fault_callback(mcpwm_oper_handle_t operator, const mcpwm_brake_event_data_t *edata, void *user_data)
static bool test_cbc_brake_on_gpio_fault_callback(mcpwm_oper_handle_t oper, const mcpwm_brake_event_data_t *edata, void *user_data)
{
esp_rom_printf("cbc brake\r\n");
return false;
}
static bool test_ost_brake_on_gpio_fault_callback(mcpwm_oper_handle_t operator, const mcpwm_brake_event_data_t *edata, void *user_data)
static bool test_ost_brake_on_gpio_fault_callback(mcpwm_oper_handle_t oper, const mcpwm_brake_event_data_t *edata, void *user_data)
{
esp_rom_printf("ost brake\r\n");
return false;
@@ -145,16 +145,16 @@ TEST_CASE("mcpwm_operator_brake_on_gpio_fault", "[mcpwm]")
mcpwm_operator_config_t operator_config = {
.group_id = 0,
};
mcpwm_oper_handle_t operator = NULL;
TEST_ESP_OK(mcpwm_new_operator(&operator_config, &operator));
TEST_ESP_OK(mcpwm_operator_connect_timer(operator, timer));
mcpwm_oper_handle_t oper = NULL;
TEST_ESP_OK(mcpwm_new_operator(&operator_config, &oper));
TEST_ESP_OK(mcpwm_operator_connect_timer(oper, timer));
printf("set brake event callbacks for operator\r\n");
mcpwm_operator_event_callbacks_t cbs = {
.on_brake_cbc = test_cbc_brake_on_gpio_fault_callback,
.on_brake_ost = test_ost_brake_on_gpio_fault_callback,
};
TEST_ESP_OK(mcpwm_operator_register_event_callbacks(operator, &cbs, NULL));
TEST_ESP_OK(mcpwm_operator_register_event_callbacks(oper, &cbs, NULL));
printf("install gpio fault\r\n");
mcpwm_gpio_fault_config_t gpio_fault_config = {
@@ -183,10 +183,10 @@ TEST_CASE("mcpwm_operator_brake_on_gpio_fault", "[mcpwm]")
.brake_mode = MCPWM_OPER_BRAKE_MODE_CBC,
.flags.cbc_recover_on_tez = true,
};
TEST_ESP_OK(mcpwm_operator_set_brake_on_fault(operator, &brake_config));
TEST_ESP_OK(mcpwm_operator_set_brake_on_fault(oper, &brake_config));
brake_config.fault = gpio_ost_fault;
brake_config.brake_mode = MCPWM_OPER_BRAKE_MODE_OST;
TEST_ESP_OK(mcpwm_operator_set_brake_on_fault(operator, &brake_config));
TEST_ESP_OK(mcpwm_operator_set_brake_on_fault(oper, &brake_config));
printf("create generators\r\n");
const int gen_a_gpio = 0;
@@ -197,9 +197,9 @@ TEST_CASE("mcpwm_operator_brake_on_gpio_fault", "[mcpwm]")
.flags.io_loop_back = true,
};
generator_config.gen_gpio_num = gen_a_gpio;
TEST_ESP_OK(mcpwm_new_generator(operator, &generator_config, &gen_a));
TEST_ESP_OK(mcpwm_new_generator(oper, &generator_config, &gen_a));
generator_config.gen_gpio_num = gen_b_gpio;
TEST_ESP_OK(mcpwm_new_generator(operator, &generator_config, &gen_b));
TEST_ESP_OK(mcpwm_new_generator(oper, &generator_config, &gen_b));
printf("set generator actions on timer event\r\n");
TEST_ESP_OK(mcpwm_generator_set_actions_on_timer_event(gen_a,
@@ -229,7 +229,7 @@ TEST_CASE("mcpwm_operator_brake_on_gpio_fault", "[mcpwm]")
// remove the fault signal
gpio_set_level(cbc_fault_gpio, 0);
// recovery
TEST_ESP_OK(mcpwm_operator_recover_from_fault(operator, gpio_cbc_fault));
TEST_ESP_OK(mcpwm_operator_recover_from_fault(oper, gpio_cbc_fault));
vTaskDelay(pdMS_TO_TICKS(40));
// should recovery automatically
TEST_ASSERT_EQUAL(0, gpio_get_level(gen_a_gpio));
@@ -241,14 +241,14 @@ TEST_CASE("mcpwm_operator_brake_on_gpio_fault", "[mcpwm]")
vTaskDelay(pdMS_TO_TICKS(10));
TEST_ASSERT_EQUAL(1, gpio_get_level(gen_b_gpio));
// can't recover because fault signal is still active
TEST_ESP_ERR(ESP_ERR_INVALID_STATE, mcpwm_operator_recover_from_fault(operator, gpio_ost_fault));
TEST_ESP_ERR(ESP_ERR_INVALID_STATE, mcpwm_operator_recover_from_fault(oper, gpio_ost_fault));
// remove the fault signal
gpio_set_level(ost_fault_gpio, 0);
vTaskDelay(pdMS_TO_TICKS(40));
// for ost brake, the generator can't recover before we manually recover it
TEST_ASSERT_EQUAL(1, gpio_get_level(gen_b_gpio));
// now it's safe to recover the operator
TEST_ESP_OK(mcpwm_operator_recover_from_fault(operator, gpio_ost_fault));
TEST_ESP_OK(mcpwm_operator_recover_from_fault(oper, gpio_ost_fault));
vTaskDelay(pdMS_TO_TICKS(40));
// should recovery now
TEST_ASSERT_EQUAL(0, gpio_get_level(gen_b_gpio));
@@ -260,7 +260,7 @@ TEST_CASE("mcpwm_operator_brake_on_gpio_fault", "[mcpwm]")
TEST_ESP_OK(mcpwm_del_fault(gpio_ost_fault));
TEST_ESP_OK(mcpwm_del_generator(gen_a));
TEST_ESP_OK(mcpwm_del_generator(gen_b));
TEST_ESP_OK(mcpwm_del_operator(operator));
TEST_ESP_OK(mcpwm_del_operator(oper));
TEST_ESP_OK(mcpwm_del_timer(timer));
}
@@ -281,9 +281,9 @@ TEST_CASE("mcpwm_operator_brake_on_soft_fault", "[mcpwm]")
mcpwm_operator_config_t operator_config = {
.group_id = 0,
};
mcpwm_oper_handle_t operator = NULL;
TEST_ESP_OK(mcpwm_new_operator(&operator_config, &operator));
TEST_ESP_OK(mcpwm_operator_connect_timer(operator, timer));
mcpwm_oper_handle_t oper = NULL;
TEST_ESP_OK(mcpwm_new_operator(&operator_config, &oper));
TEST_ESP_OK(mcpwm_operator_connect_timer(oper, timer));
printf("install soft fault\r\n");
mcpwm_soft_fault_config_t soft_fault_config = {};
@@ -296,7 +296,7 @@ TEST_CASE("mcpwm_operator_brake_on_soft_fault", "[mcpwm]")
.brake_mode = MCPWM_OPER_BRAKE_MODE_CBC,
.flags.cbc_recover_on_tez = true,
};
TEST_ESP_OK(mcpwm_operator_set_brake_on_fault(operator, &brake_config));
TEST_ESP_OK(mcpwm_operator_set_brake_on_fault(oper, &brake_config));
printf("create generators\r\n");
const int gen_a_gpio = 0;
@@ -307,9 +307,9 @@ TEST_CASE("mcpwm_operator_brake_on_soft_fault", "[mcpwm]")
.flags.io_loop_back = true,
};
generator_config.gen_gpio_num = gen_a_gpio;
TEST_ESP_OK(mcpwm_new_generator(operator, &generator_config, &gen_a));
TEST_ESP_OK(mcpwm_new_generator(oper, &generator_config, &gen_a));
generator_config.gen_gpio_num = gen_b_gpio;
TEST_ESP_OK(mcpwm_new_generator(operator, &generator_config, &gen_b));
TEST_ESP_OK(mcpwm_new_generator(oper, &generator_config, &gen_b));
printf("set generator actions on timer event\r\n");
TEST_ESP_OK(mcpwm_generator_set_actions_on_timer_event(gen_a,
@@ -344,7 +344,7 @@ TEST_CASE("mcpwm_operator_brake_on_soft_fault", "[mcpwm]")
// start the timer, so that operator can recover at a specific event (e.g. tez)
TEST_ESP_OK(mcpwm_timer_start_stop(timer, MCPWM_TIMER_START_NO_STOP));
// recover on tez
TEST_ESP_OK(mcpwm_operator_recover_from_fault(operator, soft_fault));
TEST_ESP_OK(mcpwm_operator_recover_from_fault(oper, soft_fault));
vTaskDelay(pdMS_TO_TICKS(40));
// the generator output should be recoverd automatically
TEST_ASSERT_EQUAL(0, gpio_get_level(gen_a_gpio));
@@ -352,7 +352,7 @@ TEST_CASE("mcpwm_operator_brake_on_soft_fault", "[mcpwm]")
printf("change the brake mode to ost\r\n");
brake_config.brake_mode = MCPWM_OPER_BRAKE_MODE_OST;
TEST_ESP_OK(mcpwm_operator_set_brake_on_fault(operator, &brake_config));
TEST_ESP_OK(mcpwm_operator_set_brake_on_fault(oper, &brake_config));
printf("trigger soft fault signal, brake in OST mode\r\n");
TEST_ESP_OK(mcpwm_timer_start_stop(timer, MCPWM_TIMER_START_NO_STOP));
@@ -364,7 +364,7 @@ TEST_CASE("mcpwm_operator_brake_on_soft_fault", "[mcpwm]")
vTaskDelay(pdMS_TO_TICKS(40));
// don't recover without a manual recover
TEST_ASSERT_EQUAL(1, gpio_get_level(gen_b_gpio));
TEST_ESP_OK(mcpwm_operator_recover_from_fault(operator, soft_fault));
TEST_ESP_OK(mcpwm_operator_recover_from_fault(oper, soft_fault));
vTaskDelay(pdMS_TO_TICKS(10));
// should recovery now
TEST_ASSERT_EQUAL(0, gpio_get_level(gen_b_gpio));
@@ -375,6 +375,6 @@ TEST_CASE("mcpwm_operator_brake_on_soft_fault", "[mcpwm]")
TEST_ESP_OK(mcpwm_del_fault(soft_fault));
TEST_ESP_OK(mcpwm_del_generator(gen_a));
TEST_ESP_OK(mcpwm_del_generator(gen_b));
TEST_ESP_OK(mcpwm_del_operator(operator));
TEST_ESP_OK(mcpwm_del_operator(oper));
TEST_ESP_OK(mcpwm_del_timer(timer));
}

View File

@@ -1,7 +1,10 @@
set(srcs "test_app_main.c"
"test_pulse_cnt_simulator.c"
"test_pulse_cnt.c"
"test_pulse_cnt_iram.c")
"test_pulse_cnt.c")
if(CONFIG_PCNT_ISR_IRAM_SAFE)
list(APPEND srcs "test_pulse_cnt_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

View File

@@ -10,16 +10,14 @@
#include "freertos/task.h"
#include "freertos/semphr.h"
#include "unity.h"
#include "unity_test_utils.h"
#include "driver/pulse_cnt.h"
#include "driver/gpio.h"
#include "spi_flash_mmap.h"
#include "esp_attr.h"
#include "soc/soc_caps.h"
#include "esp_private/spi_flash_os.h"
#include "test_pulse_cnt_board.h"
#if CONFIG_PCNT_ISR_IRAM_SAFE
static bool IRAM_ATTR test_pcnt_iram_safe_callback(pcnt_unit_handle_t unit, const pcnt_watch_event_data_t *event_data, void *user_data)
{
uint32_t *data = (uint32_t *)user_data;
@@ -29,13 +27,10 @@ static bool IRAM_ATTR test_pcnt_iram_safe_callback(pcnt_unit_handle_t unit, cons
return false;
}
static void IRAM_ATTR test_pcnt_iram_simulation(int gpio_sig)
static void IRAM_ATTR test_simulate_input_post_cache_disable(void *args)
{
// disable flash cache
spi_flash_guard_get()->start();
int gpio_sig = (int)args;
test_gpio_simulate_rising_edge(gpio_sig, 2);
// enable flash cache
spi_flash_guard_get()->end();
}
TEST_CASE("pcnt_iram_interrupt_safe", "[pcnt]")
@@ -83,8 +78,9 @@ TEST_CASE("pcnt_iram_interrupt_safe", "[pcnt]")
printf("disable cache and check interrupt triggered\r\n");
TEST_ESP_OK(pcnt_unit_clear_count(unit));
// the function that will disable the flash must be placed in the IRAM
test_pcnt_iram_simulation(TEST_PCNT_GPIO_A);
// disable flash cache and run simulation
unity_utils_run_cache_disable_stub(test_simulate_input_post_cache_disable, (void *)TEST_PCNT_GPIO_A);
// check if the interrupt has fired up
TEST_ASSERT_EQUAL(1, num_of_event_triggered);
@@ -101,5 +97,3 @@ TEST_CASE("pcnt_iram_interrupt_safe", "[pcnt]")
TEST_ESP_OK(pcnt_del_channel(channelB));
TEST_ESP_OK(pcnt_del_unit(unit));
}
#endif // CONFIG_PCNT_ISR_IRAM_SAFE

View File

@@ -4,5 +4,9 @@ set(srcs "test_app_main.c"
"test_rmt_rx.c"
"test_util_rmt_encoders.c")
if(CONFIG_RMT_ISR_IRAM_SAFE)
list(APPEND srcs "test_rmt_iram.c")
endif()
idf_component_register(SRCS "${srcs}"
WHOLE_ARCHIVE)

View File

@@ -0,0 +1,180 @@
/*
* SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <stdio.h>
#include <string.h>
#include "sdkconfig.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "unity.h"
#include "unity_test_utils.h"
#include "driver/rmt_tx.h"
#include "driver/rmt_rx.h"
#include "driver/gpio.h"
#include "esp_timer.h"
#include "soc/soc_caps.h"
#include "test_util_rmt_encoders.h"
static void IRAM_ATTR test_delay_post_cache_disable(void *args)
{
esp_rom_delay_us(10000);
}
static void test_rmt_tx_iram_safe(size_t mem_block_symbols, bool with_dma)
{
rmt_tx_channel_config_t tx_channel_cfg = {
.mem_block_symbols = mem_block_symbols,
.clk_src = RMT_CLK_SRC_DEFAULT,
.resolution_hz = 10000000, // 10MHz, 1 tick = 0.1us (led strip needs a high resolution)
.trans_queue_depth = 4,
.gpio_num = 0,
.flags.with_dma = with_dma,
};
printf("install tx channel\r\n");
rmt_channel_handle_t tx_channel_multi_leds = NULL;
TEST_ESP_OK(rmt_new_tx_channel(&tx_channel_cfg, &tx_channel_multi_leds));
printf("install led strip encoder\r\n");
rmt_encoder_handle_t led_strip_encoder = NULL;
TEST_ESP_OK(test_rmt_new_led_strip_encoder(&led_strip_encoder));
printf("enable tx channel\r\n");
TEST_ESP_OK(rmt_enable(tx_channel_multi_leds));
// Mutiple 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
};
const int test_led_num = 100;
uint8_t leds_grb[test_led_num * 3];
// color: Material Design Green-A200 (#69F0AE)
for (int i = 0; i < test_led_num * 3; i += 3) {
leds_grb[i + 0] = 0xF0;
leds_grb[i + 1] = 0x69;
leds_grb[i + 2] = 0xAE;
}
printf("start transmission and stop immediately, only a few LEDs are light up\r\n");
TEST_ESP_OK(rmt_transmit(tx_channel_multi_leds, led_strip_encoder, leds_grb, test_led_num * 3, &transmit_config));
// this second transmission will stay in the queue and shouldn't be dispatched until we restart the tx channel later
TEST_ESP_OK(rmt_transmit(tx_channel_multi_leds, led_strip_encoder, leds_grb, test_led_num * 3, &transmit_config));
unity_utils_run_cache_disable_stub(test_delay_post_cache_disable, NULL);
// color: Material Design Orange-900 (#E65100)
for (int i = 0; i < test_led_num * 3; i += 3) {
leds_grb[i + 0] = 0x51;
leds_grb[i + 1] = 0xE6;
leds_grb[i + 2] = 0x00;
}
TEST_ESP_OK(rmt_transmit(tx_channel_multi_leds, led_strip_encoder, leds_grb, test_led_num * 3, &transmit_config));
TEST_ESP_OK(rmt_tx_wait_all_done(tx_channel_multi_leds, -1));
printf("disable tx channel\r\n");
TEST_ESP_OK(rmt_disable(tx_channel_multi_leds));
printf("remove tx channel and led strip encoder\r\n");
TEST_ESP_OK(rmt_del_channel(tx_channel_multi_leds));
TEST_ESP_OK(rmt_del_encoder(led_strip_encoder));
}
TEST_CASE("rmt_tx_iram_safe_no_dma", "[rmt]")
{
test_rmt_tx_iram_safe(SOC_RMT_MEM_WORDS_PER_CHANNEL, false);
}
#if SOC_RMT_SUPPORT_DMA
TEST_CASE("rmt_tx_iram_safe_with_dma", "[rmt]")
{
test_rmt_tx_iram_safe(1024, true);
}
#endif
static void IRAM_ATTR test_simulate_input_post_cache_disable(void *args)
{
int gpio_num = (int)args;
// simulate input signal, should only be recognized as one RMT symbol
gpio_set_level(gpio_num, 0);
esp_rom_delay_us(50);
gpio_set_level(gpio_num, 1);
esp_rom_delay_us(50);
gpio_set_level(gpio_num, 0);
esp_rom_delay_us(20000);
}
typedef struct {
TaskHandle_t task_to_notify;
size_t received_symbol_num;
} test_nec_rx_user_data_t;
IRAM_ATTR
static bool test_rmt_rx_done_callback(rmt_channel_handle_t channel, const rmt_rx_done_event_data_t *edata, void *user_data)
{
BaseType_t high_task_wakeup = pdFALSE;
test_nec_rx_user_data_t *test_user_data = (test_nec_rx_user_data_t *)user_data;
test_user_data->received_symbol_num = edata->num_symbols;
vTaskNotifyGiveFromISR(test_user_data->task_to_notify, &high_task_wakeup);
return high_task_wakeup == pdTRUE;
}
static void test_rmt_rx_iram_safe(size_t mem_block_symbols, bool with_dma, rmt_clock_source_t clk_src)
{
rmt_rx_channel_config_t rx_channel_cfg = {
.clk_src = clk_src,
.resolution_hz = 1000000, // 1MHz, 1 tick = 1us
.mem_block_symbols = mem_block_symbols,
.gpio_num = 0,
.flags.with_dma = with_dma,
.flags.io_loop_back = true, // the GPIO will act like a loopback
};
printf("install rx channel\r\n");
rmt_channel_handle_t rx_channel = NULL;
TEST_ESP_OK(rmt_new_rx_channel(&rx_channel_cfg, &rx_channel));
// initialize the GPIO level to low
TEST_ESP_OK(gpio_set_level(0, 0));
printf("register rx event callbacks\r\n");
rmt_rx_event_callbacks_t cbs = {
.on_recv_done = test_rmt_rx_done_callback,
};
test_nec_rx_user_data_t test_user_data = {
.task_to_notify = xTaskGetCurrentTaskHandle(),
};
TEST_ESP_OK(rmt_rx_register_event_callbacks(rx_channel, &cbs, &test_user_data));
printf("enable rx channel\r\n");
TEST_ESP_OK(rmt_enable(rx_channel));
rmt_symbol_word_t remote_codes[128];
rmt_receive_config_t receive_config = {
.signal_range_min_ns = 1250,
.signal_range_max_ns = 12000000,
};
// ready to receive
TEST_ESP_OK(rmt_receive(rx_channel, remote_codes, sizeof(remote_codes), &receive_config));
// disable the flash cache, and simulate input signal by GPIO
unity_utils_run_cache_disable_stub(test_simulate_input_post_cache_disable, 0);
TEST_ASSERT_EQUAL(1, test_user_data.received_symbol_num);
printf("disable rx channels\r\n");
TEST_ESP_OK(rmt_disable(rx_channel));
printf("delete channels and encoder\r\n");
TEST_ESP_OK(rmt_del_channel(rx_channel));
}
TEST_CASE("rmt_rx_iram_safe_no_dma", "[rmt]")
{
test_rmt_rx_iram_safe(SOC_RMT_MEM_WORDS_PER_CHANNEL, false, RMT_CLK_SRC_DEFAULT);
}
#if SOC_RMT_SUPPORT_DMA
TEST_CASE("rmt_rx_iram_safe_with_dma", "[rmt]")
{
test_rmt_rx_iram_safe(128, true, RMT_CLK_SRC_DEFAULT);
}
#endif

View File

@@ -35,8 +35,8 @@ static bool test_rmt_rx_done_callback(rmt_channel_handle_t channel, const rmt_rx
for (size_t i = 0; i < edata->num_symbols; i++) {
esp_rom_printf("{%d:%d},{%d:%d}\r\n", remote_codes[i].level0, remote_codes[i].duration0, remote_codes[i].level1, remote_codes[i].duration1);
}
vTaskNotifyGiveFromISR(test_user_data->task_to_notify, &high_task_wakeup);
test_user_data->received_symbol_num = edata->num_symbols;
vTaskNotifyGiveFromISR(test_user_data->task_to_notify, &high_task_wakeup);
return high_task_wakeup == pdTRUE;
}
@@ -100,7 +100,7 @@ static void test_rmt_rx_nec_carrier(size_t mem_block_symbols, bool with_dma, rmt
0x0440, 0x3003 // address, command
}, 4, &transmit_config));
TEST_ASSERT_NOT_EQUAL(0, ulTaskNotifyTake(pdFALSE, pdMS_TO_TICKS(1000)));
TEST_ASSERT_EQUAL(test_user_data.received_symbol_num, 34);
TEST_ASSERT_EQUAL(34, test_user_data.received_symbol_num);
TEST_ESP_OK(rmt_receive(rx_channel, remote_codes, sizeof(remote_codes), &receive_config));
printf("send NEC frame without carrier\r\n");
@@ -108,7 +108,7 @@ static void test_rmt_rx_nec_carrier(size_t mem_block_symbols, bool with_dma, rmt
0x0440, 0x3003 // address, command
}, 4, &transmit_config));
TEST_ASSERT_NOT_EQUAL(0, ulTaskNotifyTake(pdFALSE, pdMS_TO_TICKS(1000)));
TEST_ASSERT_EQUAL(test_user_data.received_symbol_num, 34);
TEST_ASSERT_EQUAL(34, test_user_data.received_symbol_num);
#if SOC_RMT_SUPPORT_RX_PINGPONG
// ready to receive
@@ -118,7 +118,7 @@ static void test_rmt_rx_nec_carrier(size_t mem_block_symbols, bool with_dma, rmt
0xFF00, 0xFF00, 0xFF00, 0xFF00
}, 8, &transmit_config));
TEST_ASSERT_NOT_EQUAL(0, ulTaskNotifyTake(pdFALSE, pdMS_TO_TICKS(1000)));
TEST_ASSERT_EQUAL(test_user_data.received_symbol_num, 66);
TEST_ASSERT_EQUAL(66, test_user_data.received_symbol_num);
#else
// ready to receive
TEST_ESP_OK(rmt_receive(rx_channel, remote_codes, sizeof(remote_codes), &receive_config));
@@ -150,7 +150,7 @@ static void test_rmt_rx_nec_carrier(size_t mem_block_symbols, bool with_dma, rmt
0x0440, 0x3003 // address, command
}, 4, &transmit_config));
TEST_ASSERT_NOT_EQUAL(0, ulTaskNotifyTake(pdFALSE, pdMS_TO_TICKS(1000)));
TEST_ASSERT_EQUAL(test_user_data.received_symbol_num, 34);
TEST_ASSERT_EQUAL(34, test_user_data.received_symbol_num);
#if SOC_RMT_SUPPORT_RX_PINGPONG
TEST_ESP_OK(rmt_receive(rx_channel, remote_codes, sizeof(remote_codes), &receive_config));
@@ -159,7 +159,7 @@ static void test_rmt_rx_nec_carrier(size_t mem_block_symbols, bool with_dma, rmt
0xFF00, 0xFF00, 0xFF00, 0xFF00
}, 8, &transmit_config));
TEST_ASSERT_NOT_EQUAL(0, ulTaskNotifyTake(pdFALSE, pdMS_TO_TICKS(1000)));
TEST_ASSERT_EQUAL(test_user_data.received_symbol_num, 66);
TEST_ASSERT_EQUAL(66, test_user_data.received_symbol_num);
#endif // SOC_RMT_SUPPORT_RX_PINGPONG
printf("disable modulation and demodulation for tx and rx channels\r\n");
@@ -173,7 +173,7 @@ static void test_rmt_rx_nec_carrier(size_t mem_block_symbols, bool with_dma, rmt
0x0440, 0x3003 // address, command
}, 4, &transmit_config));
TEST_ASSERT_NOT_EQUAL(0, ulTaskNotifyTake(pdFALSE, pdMS_TO_TICKS(1000)));
TEST_ASSERT_EQUAL(test_user_data.received_symbol_num, 34);
TEST_ASSERT_EQUAL(34, test_user_data.received_symbol_num);
TEST_ESP_OK(rmt_tx_wait_all_done(tx_channel, -1));
printf("disable tx and rx channels\r\n");

View File

@@ -6,8 +6,16 @@
#include <stdio.h>
#include <string.h>
#include <sys/cdefs.h>
#include "sdkconfig.h"
#include "unity.h"
#include "driver/rmt_encoder.h"
#include "esp_attr.h"
#if CONFIG_RMT_ISR_IRAM_SAFE
#define TEST_RMT_ENCODER_ATTR IRAM_ATTR
#else
#define TEST_RMT_ENCODER_ATTR
#endif
typedef struct {
rmt_encoder_t base;
@@ -17,6 +25,7 @@ typedef struct {
rmt_symbol_word_t reset_code;
} rmt_led_strip_encoder_t;
TEST_RMT_ENCODER_ATTR
static size_t rmt_encode_led_strip(rmt_encoder_t *encoder, rmt_channel_handle_t channel, const void *primary_data, size_t data_size, rmt_encode_state_t *ret_state)
{
rmt_led_strip_encoder_t *led_encoder = __containerof(encoder, rmt_led_strip_encoder_t, base);

View File

@@ -1,5 +1,6 @@
CONFIG_COMPILER_DUMP_RTL_FILES=y
CONFIG_RMT_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

View File

@@ -764,7 +764,7 @@ static esp_err_t gdma_install_rx_interrupt(gdma_rx_channel_t *rx_chan)
// pre-alloc a interrupt handle, with handler disabled
int isr_flags = GDMA_INTR_ALLOC_FLAGS;
#if SOC_GDMA_TX_RX_SHARE_INTERRUPT
isr_flags |= ESP_INTR_FLAG_SHARED;
isr_flags |= ESP_INTR_FLAG_SHARED | ESP_INTR_FLAG_LOWMED;
#endif
intr_handle_t intr = NULL;
ret = esp_intr_alloc_intrstatus(gdma_periph_signals.groups[group->group_id].pairs[pair->pair_id].rx_irq_id, isr_flags,
@@ -791,7 +791,7 @@ static esp_err_t gdma_install_tx_interrupt(gdma_tx_channel_t *tx_chan)
// pre-alloc a interrupt handle, with handler disabled
int isr_flags = GDMA_INTR_ALLOC_FLAGS;
#if SOC_GDMA_TX_RX_SHARE_INTERRUPT
isr_flags |= ESP_INTR_FLAG_SHARED;
isr_flags |= ESP_INTR_FLAG_SHARED | ESP_INTR_FLAG_LOWMED;
#endif
intr_handle_t intr = NULL;
ret = esp_intr_alloc_intrstatus(gdma_periph_signals.groups[group->group_id].pairs[pair->pair_id].tx_irq_id, isr_flags,

View File

@@ -21,7 +21,6 @@ idf_component_register(SRCS ${srcs}
INCLUDE_DIRS ${includes}
PRIV_REQUIRES ${priv_requires}
LDFRAGMENTS linker.lf)
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")
if(CONFIG_SPIRAM)
idf_component_optional_requires(PRIVATE esp_psram)

View File

@@ -208,7 +208,7 @@ esp_err_t esp_lcd_del_i80_bus(esp_lcd_i80_bus_handle_t bus);
*/
typedef struct {
int cs_gpio_num; /*!< GPIO used for CS line, set to -1 will declaim exclusively use of I80 bus */
unsigned int pclk_hz; /*!< Frequency of pixel clock */
uint32_t pclk_hz; /*!< Frequency of pixel clock */
size_t trans_queue_depth; /*!< Transaction queue size, larger queue, higher throughput */
esp_lcd_panel_io_color_trans_done_cb_t on_color_trans_done; /*!< Callback invoked when color data was tranferred done */
void *user_ctx; /*!< User private data, passed directly to on_color_trans_done's user_ctx */

View File

@@ -18,7 +18,10 @@ extern "C" {
*/
typedef struct {
int reset_gpio_num; /*!< GPIO used to reset the LCD panel, set to -1 if it's not used */
esp_lcd_color_space_t color_space; /*!< Set the color space used by the LCD panel */
union {
lcd_color_rgb_endian_t color_space; /*!< @deprecated Set RGB color space, please use rgb_endian instead */
lcd_color_rgb_endian_t rgb_endian; /*!< Set RGB data endian: RGB or BGR */
};
unsigned int bits_per_pixel; /*!< Color depth, in bpp */
struct {
unsigned int reset_active_high: 1; /*!< Setting this if the panel reset is high level active */

View File

@@ -1,10 +1,12 @@
/*
* SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once
#include "hal/lcd_types.h"
#ifdef __cplusplus
extern "C" {
#endif
@@ -12,14 +14,22 @@ extern "C" {
typedef struct esp_lcd_panel_io_t *esp_lcd_panel_io_handle_t; /*!< Type of LCD panel IO handle */
typedef struct esp_lcd_panel_t *esp_lcd_panel_handle_t; /*!< Type of LCD panel handle */
/** @cond */
/**
* @brief LCD color space type definition
* @brief LCD color space type definition (WRONG!)
* @deprecated RGB and BGR should belong to the same color space, but this enum take them both as two different color spaces.
* If you want to use a enum to describe a color space, please use lcd_color_space_t instead.
*/
typedef enum {
ESP_LCD_COLOR_SPACE_RGB, /*!< Color space: RGB */
ESP_LCD_COLOR_SPACE_BGR, /*!< Color space: BGR */
ESP_LCD_COLOR_SPACE_MONOCHROME, /*!< Color space: monochrome */
} esp_lcd_color_space_t;
} esp_lcd_color_space_t __attribute__((deprecated));
// Ensure binary compatibility with lcd_color_rgb_endian_t
_Static_assert((lcd_color_rgb_endian_t)ESP_LCD_COLOR_SPACE_RGB == LCD_RGB_ENDIAN_RGB, "ESP_LCD_COLOR_SPACE_RGB is not compatible with LCD_RGB_ENDIAN_RGB");
_Static_assert((lcd_color_rgb_endian_t)ESP_LCD_COLOR_SPACE_BGR == LCD_RGB_ENDIAN_BGR, "ESP_LCD_COLOR_SPACE_BGR is not compatible with LCD_RGB_ENDIAN_BGR");
/** @endcond */
#ifdef __cplusplus
}

View File

@@ -95,7 +95,7 @@ struct lcd_panel_io_i80_t {
esp_lcd_panel_io_t base; // Base class of generic lcd panel io
esp_lcd_i80_bus_t *bus; // Which bus the device is attached to
int cs_gpio_num; // GPIO used for CS line
unsigned int pclk_hz; // PCLK clock frequency
uint32_t pclk_hz; // PCLK clock frequency
size_t clock_prescale; // Prescaler coefficient, determined by user's configured PCLK frequency
QueueHandle_t trans_queue; // Transaction queue, transactions in this queue are pending for scheduler to dispatch
QueueHandle_t done_queue; // Transaction done queue, transactions in this queue are finished but not recycled by the caller
@@ -170,7 +170,7 @@ esp_err_t esp_lcd_new_i80_bus(const esp_lcd_i80_bus_config_t *bus_config, esp_lc
i2s_ll_tx_reset_fifo(bus->hal.dev);
// install interrupt service, (I2S LCD mode only uses the "TX Unit", which leaves "RX Unit" for other purpose)
// So the interrupt should also be able to share with other functionality
int isr_flags = LCD_I80_INTR_ALLOC_FLAGS | ESP_INTR_FLAG_SHARED;
int isr_flags = LCD_I80_INTR_ALLOC_FLAGS | ESP_INTR_FLAG_SHARED | ESP_INTR_FLAG_LOWMED;
ret = esp_intr_alloc_intrstatus(lcd_periph_signals.buses[bus->bus_id].irq_id, isr_flags,
(uint32_t)i2s_ll_get_intr_status_reg(bus->hal.dev),
I2S_LL_EVENT_TX_EOF, lcd_default_isr_handler, bus, &bus->intr);
@@ -263,7 +263,7 @@ esp_err_t esp_lcd_new_panel_io_i80(esp_lcd_i80_bus_handle_t bus, const esp_lcd_p
// because we set the I2S's left channel data same to right channel, so f_pclk = f_i2s/pclk_div/2
uint32_t pclk_prescale = bus->resolution_hz / 2 / io_config->pclk_hz;
ESP_GOTO_ON_FALSE(pclk_prescale > 0 && pclk_prescale <= I2S_LL_BCK_MAX_PRESCALE, ESP_ERR_NOT_SUPPORTED, err, TAG,
"prescaler can't satisfy PCLK clock %u", io_config->pclk_hz);
"prescaler can't satisfy PCLK clock %"PRIu32"Hz", io_config->pclk_hz);
i80_device = heap_caps_calloc(1, sizeof(lcd_panel_io_i80_t) + io_config->trans_queue_depth * sizeof(lcd_i80_trans_descriptor_t), LCD_I80_MEM_ALLOC_CAPS);
ESP_GOTO_ON_FALSE(i80_device, ESP_ERR_NO_MEM, err, TAG, "no mem for i80 panel io");
// create two queues for i80 device
@@ -302,7 +302,7 @@ esp_err_t esp_lcd_new_panel_io_i80(esp_lcd_i80_bus_handle_t bus, const esp_lcd_p
gpio_hal_iomux_func_sel(GPIO_PIN_MUX_REG[io_config->cs_gpio_num], PIN_FUNC_GPIO);
}
*ret_io = &(i80_device->base);
ESP_LOGD(TAG, "new i80 lcd panel io @%p on bus(%d), pclk=%uHz", i80_device, bus->bus_id, i80_device->pclk_hz);
ESP_LOGD(TAG, "new i80 lcd panel io @%p on bus(%d), pclk=%"PRIu32"Hz", i80_device, bus->bus_id, i80_device->pclk_hz);
return ESP_OK;
err:

View File

@@ -153,7 +153,7 @@ esp_err_t esp_lcd_new_i80_bus(const esp_lcd_i80_bus_config_t *bus_config, esp_lc
ESP_GOTO_ON_ERROR(ret, err, TAG, "select periph clock %d failed", bus_config->clk_src);
// install interrupt service, (LCD peripheral shares the same interrupt source with Camera peripheral with different mask)
// interrupt is disabled by default
int isr_flags = LCD_I80_INTR_ALLOC_FLAGS | ESP_INTR_FLAG_SHARED;
int isr_flags = LCD_I80_INTR_ALLOC_FLAGS | ESP_INTR_FLAG_SHARED | ESP_INTR_FLAG_LOWMED;
ret = esp_intr_alloc_intrstatus(lcd_periph_signals.buses[bus_id].irq_id, isr_flags,
(uint32_t)lcd_ll_get_interrupt_status_reg(bus->hal.dev),
LCD_LL_EVENT_TRANS_DONE, lcd_default_isr_handler, bus, &bus->intr);
@@ -249,7 +249,7 @@ esp_err_t esp_lcd_new_panel_io_i80(esp_lcd_i80_bus_handle_t bus, const esp_lcd_p
// check if pixel clock setting is valid
uint32_t pclk_prescale = bus->resolution_hz / io_config->pclk_hz;
ESP_GOTO_ON_FALSE(pclk_prescale > 0 && pclk_prescale <= LCD_LL_PCLK_DIV_MAX, ESP_ERR_NOT_SUPPORTED, err, TAG,
"prescaler can't satisfy PCLK clock %u", io_config->pclk_hz);
"prescaler can't satisfy PCLK clock %"PRIu32"Hz", io_config->pclk_hz);
i80_device = heap_caps_calloc(1, sizeof(lcd_panel_io_i80_t) + io_config->trans_queue_depth * sizeof(lcd_i80_trans_descriptor_t), LCD_I80_MEM_ALLOC_CAPS);
ESP_GOTO_ON_FALSE(i80_device, ESP_ERR_NO_MEM, err, TAG, "no mem for i80 panel io");
// create two queues for i80 device

View File

@@ -66,11 +66,11 @@ esp_err_t esp_lcd_new_panel_nt35510(const esp_lcd_panel_io_handle_t io, const es
ESP_GOTO_ON_ERROR(gpio_config(&io_conf), err, TAG, "configure GPIO for RST line failed");
}
switch (panel_dev_config->color_space) {
case ESP_LCD_COLOR_SPACE_RGB:
switch (panel_dev_config->rgb_endian) {
case LCD_RGB_ENDIAN_RGB:
nt35510->madctl_val = 0;
break;
case ESP_LCD_COLOR_SPACE_BGR:
case LCD_RGB_ENDIAN_BGR:
nt35510->madctl_val |= LCD_CMD_BGR_BIT;
break;
default:

View File

@@ -66,7 +66,6 @@ esp_err_t esp_lcd_new_panel_ssd1306(const esp_lcd_panel_io_handle_t io, const es
esp_err_t ret = ESP_OK;
ssd1306_panel_t *ssd1306 = NULL;
ESP_GOTO_ON_FALSE(io && panel_dev_config && ret_panel, ESP_ERR_INVALID_ARG, err, TAG, "invalid argument");
ESP_GOTO_ON_FALSE(panel_dev_config->color_space == ESP_LCD_COLOR_SPACE_MONOCHROME, ESP_ERR_INVALID_ARG, err, TAG, "support monochrome only");
ESP_GOTO_ON_FALSE(panel_dev_config->bits_per_pixel == 1, ESP_ERR_INVALID_ARG, err, TAG, "bpp must be 1");
ssd1306 = calloc(1, sizeof(ssd1306_panel_t));
ESP_GOTO_ON_FALSE(ssd1306, ESP_ERR_NO_MEM, err, TAG, "no mem for ssd1306 panel");

View File

@@ -66,11 +66,11 @@ esp_err_t esp_lcd_new_panel_st7789(const esp_lcd_panel_io_handle_t io, const esp
ESP_GOTO_ON_ERROR(gpio_config(&io_conf), err, TAG, "configure GPIO for RST line failed");
}
switch (panel_dev_config->color_space) {
case ESP_LCD_COLOR_SPACE_RGB:
switch (panel_dev_config->rgb_endian) {
case LCD_RGB_ENDIAN_RGB:
st7789->madctl_val = 0;
break;
case ESP_LCD_COLOR_SPACE_BGR:
case LCD_RGB_ENDIAN_BGR:
st7789->madctl_val |= LCD_CMD_BGR_BIT;
break;
default:

View File

@@ -278,7 +278,7 @@ esp_err_t esp_lcd_new_rgb_panel(const esp_lcd_rgb_panel_config_t *rgb_panel_conf
rgb_panel->lcd_clk_flags |= LCD_HAL_PCLK_FLAG_ALLOW_EQUAL_SYSCLK;
}
// install interrupt service, (LCD peripheral shares the interrupt source with Camera by different mask)
int isr_flags = LCD_RGB_INTR_ALLOC_FLAGS | ESP_INTR_FLAG_SHARED;
int isr_flags = LCD_RGB_INTR_ALLOC_FLAGS | ESP_INTR_FLAG_SHARED | ESP_INTR_FLAG_LOWMED;
ret = esp_intr_alloc_intrstatus(lcd_periph_signals.panels[panel_id].irq_id, isr_flags,
(uint32_t)lcd_ll_get_interrupt_status_reg(rgb_panel->hal.dev),
LCD_LL_EVENT_VSYNC_END, lcd_default_isr_handler, rgb_panel, &rgb_panel->intr);
@@ -444,7 +444,7 @@ static esp_err_t rgb_panel_init(esp_lcd_panel_t *panel)
if (rgb_panel->flags.stream_mode) {
lcd_rgb_panel_start_transmission(rgb_panel);
}
ESP_LOGD(TAG, "rgb panel(%d) start, pclk=%uHz", rgb_panel->panel_id, rgb_panel->timings.pclk_hz);
ESP_LOGD(TAG, "rgb panel(%d) start, pclk=%"PRIu32"Hz", rgb_panel->panel_id, rgb_panel->timings.pclk_hz);
return ret;
}

View File

@@ -50,7 +50,6 @@ TEST_CASE("lcd_panel_with_i2c_interface_(ssd1306)", "[lcd]")
esp_lcd_panel_handle_t panel_handle = NULL;
esp_lcd_panel_dev_config_t panel_config = {
.bits_per_pixel = 1,
.color_space = ESP_LCD_COLOR_SPACE_MONOCHROME,
.reset_gpio_num = -1,
};
TEST_ESP_OK(esp_lcd_new_panel_ssd1306(io_handle, &panel_config, &panel_handle));

View File

@@ -299,7 +299,7 @@ TEST_CASE("lcd_panel_i80_io_test", "[lcd]")
esp_lcd_panel_handle_t panel_handle = NULL;
esp_lcd_panel_dev_config_t panel_config = {
.reset_gpio_num = TEST_LCD_RST_GPIO,
.color_space = ESP_LCD_COLOR_SPACE_RGB,
.rgb_endian = LCD_RGB_ENDIAN_RGB,
.bits_per_pixel = 16,
};
@@ -419,7 +419,7 @@ TEST_CASE("lcd_panel_with_i80_interface_(st7789, 8bits)", "[lcd]")
esp_lcd_panel_handle_t panel_handle = NULL;
esp_lcd_panel_dev_config_t panel_config = {
.reset_gpio_num = TEST_LCD_RST_GPIO,
.color_space = ESP_LCD_COLOR_SPACE_RGB,
.rgb_endian = LCD_RGB_ENDIAN_RGB,
.bits_per_pixel = 16,
};
TEST_ESP_OK(esp_lcd_new_panel_st7789(io_handle, &panel_config, &panel_handle));

View File

@@ -5,4 +5,3 @@ set(srcs "test_app_main.c"
# the component can be registered as WHOLE_ARCHIVE
idf_component_register(SRCS ${srcs}
WHOLE_ARCHIVE)
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

View File

@@ -5,6 +5,7 @@
*/
#include <stdio.h>
#include <string.h>
#include <inttypes.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "unity.h"
@@ -281,7 +282,7 @@ TEST_CASE("lcd_rgb_panel_iram_safe", "[lcd]")
printf("disable the cache for a while\r\n");
test_disable_flash_cache();
printf("the RGB ISR handle should keep working while the flash cache is disabled\r\n");
printf("callback calls: %d\r\n", callback_calls);
printf("callback calls: %"PRIu32"\r\n", callback_calls);
TEST_ASSERT(callback_calls > 2);
printf("delete RGB panel\r\n");

View File

@@ -150,7 +150,7 @@ TEST_CASE("lcd_panel_with_8-line_spi_interface_(st7789)", "[lcd]")
test_spi_lcd_common_initialize(&io_handle, NULL, NULL, 8, 8, true);
esp_lcd_panel_dev_config_t panel_config = {
.reset_gpio_num = TEST_LCD_RST_GPIO,
.color_space = ESP_LCD_COLOR_SPACE_RGB,
.rgb_endian = LCD_RGB_ENDIAN_RGB,
.bits_per_pixel = 16,
};
TEST_ESP_OK(esp_lcd_new_panel_st7789(io_handle, &panel_config, &panel_handle));
@@ -164,7 +164,7 @@ TEST_CASE("lcd_panel_with_8-line_spi_interface_(nt35510)", "[lcd]")
test_spi_lcd_common_initialize(&io_handle, NULL, NULL, 16, 16, true);
esp_lcd_panel_dev_config_t panel_config = {
.reset_gpio_num = TEST_LCD_RST_GPIO,
.color_space = ESP_LCD_COLOR_SPACE_RGB,
.rgb_endian = LCD_RGB_ENDIAN_RGB,
.bits_per_pixel = 16,
};
TEST_ESP_OK(esp_lcd_new_panel_nt35510(io_handle, &panel_config, &panel_handle));
@@ -179,7 +179,7 @@ TEST_CASE("lcd_panel_with_1-line_spi_interface_(st7789)", "[lcd]")
test_spi_lcd_common_initialize(&io_handle, NULL, NULL, 8, 8, false);
esp_lcd_panel_dev_config_t panel_config = {
.reset_gpio_num = TEST_LCD_RST_GPIO,
.color_space = ESP_LCD_COLOR_SPACE_RGB,
.rgb_endian = LCD_RGB_ENDIAN_RGB,
.bits_per_pixel = 16,
};
TEST_ESP_OK(esp_lcd_new_panel_st7789(io_handle, &panel_config, &panel_handle));

View File

@@ -504,48 +504,57 @@ static inline uint32_t rmt_ll_rx_get_interrupt_status(rmt_dev_t *dev, uint32_t c
/////////////////////////////They might be removed in the next major release (ESP-IDF 6.0)//////////////////////////////
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_status_word(rmt_dev_t *dev, uint32_t channel)
{
return dev->status_ch[channel];
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_status_word(rmt_dev_t *dev, uint32_t channel)
{
return dev->status_ch[channel];
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_channel_clock_div(rmt_dev_t *dev, uint32_t channel)
{
uint32_t div = HAL_FORCE_READ_U32_REG_FIELD(dev->conf_ch[channel].conf0, div_cnt);
return div == 0 ? 256 : div;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_channel_clock_div(rmt_dev_t *dev, uint32_t channel)
{
uint32_t div = HAL_FORCE_READ_U32_REG_FIELD(dev->conf_ch[channel].conf0, div_cnt);
return div == 0 ? 256 : div;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_idle_thres(rmt_dev_t *dev, uint32_t channel)
{
return HAL_FORCE_READ_U32_REG_FIELD(dev->conf_ch[channel].conf0, idle_thres);
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_mem_blocks(rmt_dev_t *dev, uint32_t channel)
{
return dev->conf_ch[channel].conf0.mem_size;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_mem_blocks(rmt_dev_t *dev, uint32_t channel)
{
return dev->conf_ch[channel].conf0.mem_size;
}
__attribute__((always_inline))
static inline bool rmt_ll_tx_is_loop_enabled(rmt_dev_t *dev, uint32_t channel)
{
return dev->conf_ch[channel].conf1.tx_conti_mode;
}
__attribute__((always_inline))
static inline rmt_clock_source_t rmt_ll_get_group_clock_src(rmt_dev_t *dev, uint32_t channel)
{
if (dev->conf_ch[channel].conf1.ref_always_on) {
@@ -554,11 +563,13 @@ static inline rmt_clock_source_t rmt_ll_get_group_clock_src(rmt_dev_t *dev, uint
return RMT_CLK_SRC_REF_TICK;
}
__attribute__((always_inline))
static inline bool rmt_ll_tx_is_idle_enabled(rmt_dev_t *dev, uint32_t channel)
{
return dev->conf_ch[channel].conf1.idle_out_en;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_idle_level(rmt_dev_t *dev, uint32_t channel)
{
return dev->conf_ch[channel].conf1.idle_out_lv;
@@ -570,11 +581,13 @@ static inline bool rmt_ll_is_mem_powered_down(rmt_dev_t *dev)
return dev->conf_ch[0].conf0.mem_pd;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_mem_owner(rmt_dev_t *dev, uint32_t channel)
{
return dev->conf_ch[channel].conf1.mem_owner;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_tx_end_interrupt_status(rmt_dev_t *dev)
{
uint32_t status = dev->int_st.val;
@@ -582,6 +595,7 @@ static inline uint32_t rmt_ll_get_tx_end_interrupt_status(rmt_dev_t *dev)
((status & 0x1000) >> 8) | ((status & 0x8000) >> 10) | ((status & 0x40000) >> 12) | ((status & 0x200000) >> 14);
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_rx_end_interrupt_status(rmt_dev_t *dev)
{
uint32_t status = dev->int_st.val;
@@ -589,6 +603,7 @@ static inline uint32_t rmt_ll_get_rx_end_interrupt_status(rmt_dev_t *dev)
((status & 0x2000) >> 9) | ((status & 0x10000) >> 11) | ((status & 0x80000) >> 13) | ((status & 0x400000) >> 15);
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_tx_err_interrupt_status(rmt_dev_t *dev)
{
uint32_t status = dev->int_st.val;
@@ -596,6 +611,7 @@ static inline uint32_t rmt_ll_get_tx_err_interrupt_status(rmt_dev_t *dev)
((status & 0x4000) >> 10) | ((status & 0x20000) >> 12) | ((status & 0x100000) >> 14) | ((status & 0x800000) >> 16);
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_rx_err_interrupt_status(rmt_dev_t *dev)
{
uint32_t status = dev->int_st.val;
@@ -603,6 +619,7 @@ static inline uint32_t rmt_ll_get_rx_err_interrupt_status(rmt_dev_t *dev)
((status & 0x4000) >> 10) | ((status & 0x20000) >> 12) | ((status & 0x100000) >> 14) | ((status & 0x800000) >> 16);
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_tx_thres_interrupt_status(rmt_dev_t *dev)
{
uint32_t status = dev->int_st.val;

View File

@@ -684,48 +684,57 @@ static inline uint32_t rmt_ll_rx_get_interrupt_status(rmt_dev_t *dev, uint32_t c
/////////////////////////////They might be removed in the next major release (ESP-IDF 6.0)//////////////////////////////
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_status_word(rmt_dev_t *dev, uint32_t channel)
{
return dev->tx_status[channel].val;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_status_word(rmt_dev_t *dev, uint32_t channel)
{
return dev->rx_status[channel].val;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_channel_clock_div(rmt_dev_t *dev, uint32_t channel)
{
uint32_t div = HAL_FORCE_READ_U32_REG_FIELD(dev->tx_conf[channel], div_cnt);
return div == 0 ? 256 : div;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_channel_clock_div(rmt_dev_t *dev, uint32_t channel)
{
uint32_t div = HAL_FORCE_READ_U32_REG_FIELD(dev->rx_conf[channel].conf0, div_cnt);
return div == 0 ? 256 : div;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_idle_thres(rmt_dev_t *dev, uint32_t channel)
{
return dev->rx_conf[channel].conf0.idle_thres;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_mem_blocks(rmt_dev_t *dev, uint32_t channel)
{
return dev->tx_conf[channel].mem_size;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_mem_blocks(rmt_dev_t *dev, uint32_t channel)
{
return dev->rx_conf[channel].conf0.mem_size;
}
__attribute__((always_inline))
static inline bool rmt_ll_tx_is_loop_enabled(rmt_dev_t *dev, uint32_t channel)
{
return dev->tx_conf[channel].tx_conti_mode;
}
__attribute__((always_inline))
static inline rmt_clock_source_t rmt_ll_get_group_clock_src(rmt_dev_t *dev, uint32_t channel)
{
rmt_clock_source_t clk_src = RMT_CLK_SRC_APB;
@@ -743,11 +752,13 @@ static inline rmt_clock_source_t rmt_ll_get_group_clock_src(rmt_dev_t *dev, uint
return clk_src;
}
__attribute__((always_inline))
static inline bool rmt_ll_tx_is_idle_enabled(rmt_dev_t *dev, uint32_t channel)
{
return dev->tx_conf[channel].idle_out_en;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_idle_level(rmt_dev_t *dev, uint32_t channel)
{
return dev->tx_conf[channel].idle_out_lv;
@@ -761,46 +772,55 @@ static inline bool rmt_ll_is_mem_powered_down(rmt_dev_t *dev)
return (dev->sys_conf.mem_force_pd) || !(dev->sys_conf.mem_force_pu);
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_mem_owner(rmt_dev_t *dev, uint32_t channel)
{
return dev->rx_conf[channel].conf1.mem_owner;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_limit(rmt_dev_t *dev, uint32_t channel)
{
return dev->rx_lim[channel].rx_lim;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_tx_end_interrupt_status(rmt_dev_t *dev)
{
return dev->int_st.val & 0x03;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_rx_end_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 2) & 0x03;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_tx_err_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 4) & 0x03;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_rx_err_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 6) & 0x03;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_tx_thres_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 8) & 0x03;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_rx_thres_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 10) & 0x03;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_tx_loop_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 12) & 0x03;

View File

@@ -684,48 +684,57 @@ static inline uint32_t rmt_ll_rx_get_interrupt_status(rmt_dev_t *dev, uint32_t c
/////////////////////////////They might be removed in the next major release (ESP-IDF 6.0)//////////////////////////////
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_status_word(rmt_dev_t *dev, uint32_t channel)
{
return dev->tx_status[channel].val;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_status_word(rmt_dev_t *dev, uint32_t channel)
{
return dev->rx_status[channel].val;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_channel_clock_div(rmt_dev_t *dev, uint32_t channel)
{
uint32_t div = HAL_FORCE_READ_U32_REG_FIELD(dev->tx_conf[channel], div_cnt);
return div == 0 ? 256 : div;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_channel_clock_div(rmt_dev_t *dev, uint32_t channel)
{
uint32_t div = HAL_FORCE_READ_U32_REG_FIELD(dev->rx_conf[channel].conf0, div_cnt);
return div == 0 ? 256 : div;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_idle_thres(rmt_dev_t *dev, uint32_t channel)
{
return dev->rx_conf[channel].conf0.idle_thres;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_mem_blocks(rmt_dev_t *dev, uint32_t channel)
{
return dev->tx_conf[channel].mem_size;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_mem_blocks(rmt_dev_t *dev, uint32_t channel)
{
return dev->rx_conf[channel].conf0.mem_size;
}
__attribute__((always_inline))
static inline bool rmt_ll_tx_is_loop_enabled(rmt_dev_t *dev, uint32_t channel)
{
return dev->tx_conf[channel].tx_conti_mode;
}
__attribute__((always_inline))
static inline rmt_clock_source_t rmt_ll_get_group_clock_src(rmt_dev_t *dev, uint32_t channel)
{
rmt_clock_source_t clk_src = RMT_CLK_SRC_AHB;
@@ -743,11 +752,13 @@ static inline rmt_clock_source_t rmt_ll_get_group_clock_src(rmt_dev_t *dev, uint
return clk_src;
}
__attribute__((always_inline))
static inline bool rmt_ll_tx_is_idle_enabled(rmt_dev_t *dev, uint32_t channel)
{
return dev->tx_conf[channel].idle_out_en;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_idle_level(rmt_dev_t *dev, uint32_t channel)
{
return dev->tx_conf[channel].idle_out_lv;
@@ -761,46 +772,55 @@ static inline bool rmt_ll_is_mem_powered_down(rmt_dev_t *dev)
return (dev->sys_conf.mem_force_pd) || !(dev->sys_conf.mem_force_pu);
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_mem_owner(rmt_dev_t *dev, uint32_t channel)
{
return dev->rx_conf[channel].conf1.mem_owner;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_limit(rmt_dev_t *dev, uint32_t channel)
{
return dev->rx_lim[channel].rx_lim;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_tx_end_interrupt_status(rmt_dev_t *dev)
{
return dev->int_st.val & 0x03;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_rx_end_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 2) & 0x03;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_tx_err_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 4) & 0x03;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_rx_err_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 6) & 0x03;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_tx_thres_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 8) & 0x03;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_rx_thres_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 10) & 0x03;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_tx_loop_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 12) & 0x03;

View File

@@ -649,48 +649,57 @@ static inline uint32_t rmt_ll_rx_get_interrupt_status(rmt_dev_t *dev, uint32_t c
/////////////////////////////They might be removed in the next major release (ESP-IDF 6.0)//////////////////////////////
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_status_word(rmt_dev_t *dev, uint32_t channel)
{
return dev->chnstatus[channel].val;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_status_word(rmt_dev_t *dev, uint32_t channel)
{
return dev->chnstatus[channel].val;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_channel_clock_div(rmt_dev_t *dev, uint32_t channel)
{
uint32_t div = HAL_FORCE_READ_U32_REG_FIELD(dev->conf_ch[channel].conf0, div_cnt_chn);
return div == 0 ? 256 : div;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_channel_clock_div(rmt_dev_t *dev, uint32_t channel)
{
uint32_t div = HAL_FORCE_READ_U32_REG_FIELD(dev->conf_ch[channel].conf0, div_cnt_chn);
return div == 0 ? 256 : div;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_idle_thres(rmt_dev_t *dev, uint32_t channel)
{
return HAL_FORCE_READ_U32_REG_FIELD(dev->conf_ch[channel].conf0, idle_thres_chn);
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_mem_blocks(rmt_dev_t *dev, uint32_t channel)
{
return dev->conf_ch[channel].conf0.mem_size_chn;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_mem_blocks(rmt_dev_t *dev, uint32_t channel)
{
return dev->conf_ch[channel].conf0.mem_size_chn;
}
__attribute__((always_inline))
static inline bool rmt_ll_tx_is_loop_enabled(rmt_dev_t *dev, uint32_t channel)
{
return dev->conf_ch[channel].conf1.tx_conti_mode_chn;
}
__attribute__((always_inline))
static inline rmt_clock_source_t rmt_ll_get_group_clock_src(rmt_dev_t *dev, uint32_t channel)
{
if (dev->conf_ch[channel].conf1.ref_always_on_chn) {
@@ -699,11 +708,13 @@ static inline rmt_clock_source_t rmt_ll_get_group_clock_src(rmt_dev_t *dev, uint
return RMT_CLK_SRC_REF_TICK;
}
__attribute__((always_inline))
static inline bool rmt_ll_tx_is_idle_enabled(rmt_dev_t *dev, uint32_t channel)
{
return dev->conf_ch[channel].conf1.idle_out_en_chn;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_idle_level(rmt_dev_t *dev, uint32_t channel)
{
return dev->conf_ch[channel].conf1.idle_out_lv_chn;
@@ -717,41 +728,48 @@ static inline bool rmt_ll_is_mem_powered_down(rmt_dev_t *dev)
return (dev->apb_conf.mem_force_pd) || !(dev->apb_conf.mem_force_pu);
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_mem_owner(rmt_dev_t *dev, uint32_t channel)
{
return dev->conf_ch[channel].conf1.mem_owner_chn;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_tx_end_interrupt_status(rmt_dev_t *dev)
{
uint32_t status = dev->int_st.val;
return ((status & 0x01) >> 0) | ((status & 0x08) >> 2) | ((status & 0x40) >> 4) | ((status & 0x200) >> 6);
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_rx_end_interrupt_status(rmt_dev_t *dev)
{
uint32_t status = dev->int_st.val;
return ((status & 0x02) >> 1) | ((status & 0x10) >> 3) | ((status & 0x80) >> 5) | ((status & 0x400) >> 7);
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_tx_err_interrupt_status(rmt_dev_t *dev)
{
uint32_t status = dev->int_st.val;
return ((status & 0x04) >> 2) | ((status & 0x20) >> 4) | ((status & 0x100) >> 6) | ((status & 0x800) >> 8);
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_rx_err_interrupt_status(rmt_dev_t *dev)
{
uint32_t status = dev->int_st.val;
return ((status & 0x04) >> 2) | ((status & 0x20) >> 4) | ((status & 0x100) >> 6) | ((status & 0x800) >> 8);
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_tx_thres_interrupt_status(rmt_dev_t *dev)
{
uint32_t status = dev->int_st.val;
return (status & 0xF000) >> 12;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_tx_loop_interrupt_status(rmt_dev_t *dev)
{
uint32_t status = dev->int_st.val;

View File

@@ -722,48 +722,57 @@ static inline uint32_t rmt_ll_rx_get_interrupt_status(rmt_dev_t *dev, uint32_t c
/////////////////////////////They might be removed in the next major release (ESP-IDF 6.0)//////////////////////////////
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_status_word(rmt_dev_t *dev, uint32_t channel)
{
return dev->chnstatus[channel].val;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_status_word(rmt_dev_t *dev, uint32_t channel)
{
return dev->chmstatus[channel].val;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_channel_clock_div(rmt_dev_t *dev, uint32_t channel)
{
uint32_t div = HAL_FORCE_READ_U32_REG_FIELD(dev->chnconf0[channel], div_cnt_chn);
return div == 0 ? 256 : div;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_channel_clock_div(rmt_dev_t *dev, uint32_t channel)
{
uint32_t div = HAL_FORCE_READ_U32_REG_FIELD(dev->chmconf[channel].conf0, div_cnt_chm);
return div == 0 ? 256 : div;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_idle_thres(rmt_dev_t *dev, uint32_t channel)
{
return dev->chmconf[channel].conf0.idle_thres_chm;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_mem_blocks(rmt_dev_t *dev, uint32_t channel)
{
return dev->chnconf0[channel].mem_size_chn;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_mem_blocks(rmt_dev_t *dev, uint32_t channel)
{
return dev->chmconf[channel].conf0.mem_size_chm;
}
__attribute__((always_inline))
static inline bool rmt_ll_tx_is_loop_enabled(rmt_dev_t *dev, uint32_t channel)
{
return dev->chnconf0[channel].tx_conti_mode_chn;
}
__attribute__((always_inline))
static inline rmt_clock_source_t rmt_ll_get_group_clock_src(rmt_dev_t *dev, uint32_t channel)
{
rmt_clock_source_t clk_src = RMT_CLK_SRC_APB;
@@ -781,11 +790,13 @@ static inline rmt_clock_source_t rmt_ll_get_group_clock_src(rmt_dev_t *dev, uint
return clk_src;
}
__attribute__((always_inline))
static inline bool rmt_ll_tx_is_idle_enabled(rmt_dev_t *dev, uint32_t channel)
{
return dev->chnconf0[channel].idle_out_en_chn;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_tx_get_idle_level(rmt_dev_t *dev, uint32_t channel)
{
return dev->chnconf0[channel].idle_out_lv_chn;
@@ -799,46 +810,55 @@ static inline bool rmt_ll_is_mem_powered_down(rmt_dev_t *dev)
return (dev->sys_conf.mem_force_pd) || !(dev->sys_conf.mem_force_pu);
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_mem_owner(rmt_dev_t *dev, uint32_t channel)
{
return dev->chmconf[channel].conf1.mem_owner_chm;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_rx_get_limit(rmt_dev_t *dev, uint32_t channel)
{
return dev->chm_rx_lim[channel].rx_lim_chm;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_tx_end_interrupt_status(rmt_dev_t *dev)
{
return dev->int_st.val & 0x0F;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_rx_end_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 16) & 0x0F;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_tx_err_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 4) & 0x0F;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_rx_err_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 20) & 0x0F;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_tx_thres_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 8) & 0x0F;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_rx_thres_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 24) & 0x0F;
}
__attribute__((always_inline))
static inline uint32_t rmt_ll_get_tx_loop_interrupt_status(rmt_dev_t *dev)
{
return (dev->int_st.val >> 12) & 0x0F;

View File

@@ -20,6 +20,14 @@ extern "C" {
typedef soc_periph_lcd_clk_src_t lcd_clock_source_t;
#endif
/**
* @brief RGB color endian
*/
typedef enum {
LCD_RGB_ENDIAN_RGB, /*!< RGB data endian: RGB */
LCD_RGB_ENDIAN_BGR, /*!< RGB data endian: BGR */
} lcd_color_rgb_endian_t;
#ifdef __cplusplus
}
#endif

View File

@@ -17,7 +17,7 @@ if(CONFIG_UNITY_ENABLE_IDF_TEST_RUNNER)
list(APPEND srcs "unity_runner.c")
# Note the following files are not compatible with the Linux target.
# On Linux, these are masked because we also don't use the IDF test runner there
list(APPEND srcs "unity_utils_freertos.c")
list(APPEND srcs "unity_utils_freertos.c" "unity_utils_cache.c")
list(APPEND requires "freertos")
endif()
@@ -39,6 +39,10 @@ idf_component_register(SRCS "${srcs}"
INCLUDE_DIRS ${includes}
REQUIRES ${requires})
if(CONFIG_UNITY_ENABLE_IDF_TEST_RUNNER)
idf_component_optional_requires(PRIVATE spi_flash)
endif()
if(NOT "${target}" STREQUAL "linux")
target_compile_definitions(${COMPONENT_LIB} PUBLIC
-DUNITY_INCLUDE_CONFIG_H

View File

@@ -10,6 +10,7 @@
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "unity_test_utils_memory.h"
#include "unity_test_utils_cache.h"
#ifdef __cplusplus
extern "C" {

View File

@@ -0,0 +1,25 @@
/*
* SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Disable flash cache and run user stub function and then enable flash cache again
*
* @note You should make sure the passed-in function is in internal RAM.
*
* @param post_cache_disable User function to be invoked after cache is disabled.
* @param user_ctx User context to be passed to user function.
*/
void unity_utils_run_cache_disable_stub(void (*post_cache_disable)(void *), void *user_ctx);
#ifdef __cplusplus
}
#endif

View File

@@ -0,0 +1,22 @@
/*
* SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include "unity.h"
#include "unity_test_utils_cache.h"
#include "esp_attr.h"
#include "esp_memory_utils.h"
#include "esp_private/spi_flash_os.h"
IRAM_ATTR void unity_utils_run_cache_disable_stub(void (*post_cache_disable)(void *), void *user_ctx)
{
// callback function must reside in IRAM
TEST_ASSERT_TRUE(esp_ptr_in_iram(post_cache_disable));
// disable flash cache
spi_flash_guard_get()->start();
post_cache_disable(user_ctx);
// enable flash cache
spi_flash_guard_get()->end();
}

View File

@@ -814,6 +814,11 @@ The parameter ``user_data`` of :cpp:func:`mcpwm_capture_channel_register_event_c
This function will lazy install interrupt service for the MCPWM capture channel, whereas the service can only be removed in :cpp:type:`mcpwm_del_capture_channel`.
Enable and Disable Capture Channel
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
The capture channel is not enabled after allocation by :cpp:func:`mcpwm_new_capture_channel`. You should call :cpp:func:`mcpwm_capture_channel_enable` and :cpp:func:`mcpwm_capture_channel_disable` accordingly to enable or disable the channel. If the interrupt service is lazy installed during registering event callbacks for the channel in :cpp:func:`mcpwm_capture_channel_register_event_callbacks`, :cpp:func:`mcpwm_capture_channel_enable` will enable the interrupt service as well.
Enable and Disable Capture Timer
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

View File

@@ -254,6 +254,7 @@ LCD
- The way to register RGB panel event callbacks has been moved from the :cpp:type:`esp_lcd_rgb_panel_config_t` into a separate API :cpp:func:`esp_lcd_rgb_panel_register_event_callbacks`. However, the event callback signature is not changed.
- Previous ``relax_on_idle`` flag in :cpp:type:`esp_lcd_rgb_panel_config_t` has been renamed into :cpp:member:`esp_lcd_rgb_panel_config_t::refresh_on_demand`, which expresses the same meaning but with a clear name.
- If the RGB LCD is created with the ``refresh_on_demand`` flag enabled, the driver won't start a refresh in the :cpp:func:`esp_lcd_panel_draw_bitmap`. Now you have to call :cpp:func:`esp_lcd_rgb_panel_refresh` to refresh the screen by yourself.
- :cpp:type:`esp_lcd_color_space_t` is deprecated, please use :cpp:type:`lcd_color_space_t` to describe the color space, and use :cpp:type:`lcd_color_rgb_endian_t` to describe the data order of RGB color.
.. only:: SOC_MCPWM_SUPPORTED
@@ -308,7 +309,7 @@ LCD
- ``mcpwm_fault_set_oneshot_mode``, ``mcpwm_fault_set_cyc_mode`` are replaced by :cpp:func:`mcpwm_operator_set_brake_on_fault` and :cpp:func:`mcpwm_generator_set_actions_on_brake_event`.
- ``mcpwm_capture_enable`` is removed. It's duplicated to :cpp:func:`mcpwm_capture_enable_channel`.
- ``mcpwm_capture_disable`` is removed. It's duplicated to :cpp:func:`mcpwm_capture_capture_disable_channel`.
- ``mcpwm_capture_enable_channel`` and ``mcpwm_capture_disable_channel`` are replaced by :cpp:func:`mcpwm_new_capture_channel` and :cpp:func:`mcpwm_del_capture_channel`.
- ``mcpwm_capture_enable_channel`` and ``mcpwm_capture_disable_channel`` are replaced by :cpp:func:`mcpwm_capture_channel_enable` and :cpp:func:`mcpwm_capture_channel_disable`.
- ``mcpwm_capture_signal_get_value`` and ``mcpwm_capture_signal_get_edge``: Capture timer count value and capture edge are provided in the capture event callback, via :cpp:type:`mcpwm_capture_event_data_t`. Capture data are only valuable when capture event happens. Providing single API to fetch capture data is meaningless.
- ``mcpwm_sync_enable`` is removed. It's duplicated to :cpp:func:`mcpwm_sync_configure`.
- ``mcpwm_sync_configure`` is replaced by :cpp:func:`mcpwm_timer_set_phase_on_sync`.

View File

@@ -1,9 +0,0 @@
set(srcs "src/led_strip_api.c")
if(CONFIG_SOC_RMT_SUPPORTED)
list(APPEND srcs "src/led_strip_rmt_dev.c" "src/led_strip_rmt_encoder.c")
endif()
idf_component_register(SRCS ${srcs}
INCLUDE_DIRS "include" "interface"
PRIV_REQUIRES "driver")

View File

@@ -1,15 +0,0 @@
# LED Strip Component
This directory contains an implementation for addressable LEDs by different peripherals. Currently only RMT is supported as the led strip backend.
It's compatible with:
* [WS2812](http://www.world-semi.com/Certifications/WS2812B.html)
* SK68XX
This component is used as part of the following ESP-IDF examples:
- [Blink Example](../../get-started/blink).
To learn more about how to use this component, please check API Documentation from header file [led_strip.h](./include/led_strip.h).
Please note that this component is not considered to be a part of ESP-IDF stable API. It may change and it may be removed in the future releases.

View File

@@ -1,95 +0,0 @@
/*
* SPDX-FileCopyrightText: 2019-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once
#include <stdint.h>
#include "esp_err.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief LED strip handle
*/
typedef struct led_strip_t *led_strip_handle_t;
/**
* @brief Set RGB for a specific pixel
*
* @param strip: LED strip
* @param index: index of pixel to set
* @param red: red part of color
* @param green: green part of color
* @param blue: blue part of color
*
* @return
* - ESP_OK: Set RGB for a specific pixel successfully
* - ESP_ERR_INVALID_ARG: Set RGB for a specific pixel failed because of invalid parameters
* - ESP_FAIL: Set RGB for a specific pixel failed because other error occurred
*/
esp_err_t led_strip_set_pixel(led_strip_handle_t strip, uint32_t index, uint32_t red, uint32_t green, uint32_t blue);
/**
* @brief Refresh memory colors to LEDs
*
* @param strip: LED strip
*
* @return
* - ESP_OK: Refresh successfully
* - ESP_FAIL: Refresh failed because some other error occurred
*
* @note:
* After updating the LED colors in the memory, a following invocation of this API is needed to flush colors to strip.
*/
esp_err_t led_strip_refresh(led_strip_handle_t strip);
/**
* @brief Clear LED strip (turn off all LEDs)
*
* @param strip: LED strip
*
* @return
* - ESP_OK: Clear LEDs successfully
* - ESP_FAIL: Clear LEDs failed because some other error occurred
*/
esp_err_t led_strip_clear(led_strip_handle_t strip);
/**
* @brief Free LED strip resources
*
* @param strip: LED strip
*
* @return
* - ESP_OK: Free resources successfully
* - ESP_FAIL: Free resources failed because error occurred
*/
esp_err_t led_strip_del(led_strip_handle_t strip);
/**
* @brief LED Strip Configuration
*/
typedef struct {
uint32_t strip_gpio_num; /*!< GPIO number that used by LED strip */
uint32_t max_leds; /*!< Maximum LEDs in a single strip */
} led_strip_config_t;
/**
* @brief Create LED strip based on RMT TX channel
*
* @param config LED strip specific configuration
* @param ret_strip Returned LED strip handle
* @return
* - ESP_OK: create LED strip handle successfully
* - ESP_ERR_INVALID_ARG: create LED strip handle failed because of invalid argument
* - ESP_ERR_NO_MEM: create LED strip handle failed because of out of memory
* - ESP_FAIL: create LED strip handle failed because some other error
*/
esp_err_t led_strip_new_rmt_device(const led_strip_config_t *config, led_strip_handle_t *ret_strip);
#ifdef __cplusplus
}
#endif

View File

@@ -1,78 +0,0 @@
/*
* SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once
#include <stdint.h>
#include "esp_err.h"
#ifdef __cplusplus
extern "C" {
#endif
typedef struct led_strip_t led_strip_t; /*!< Type of LED strip */
/**
* @brief LED strip interface definition
*/
struct led_strip_t {
/**
* @brief Set RGB for a specific pixel
*
* @param strip: LED strip
* @param index: index of pixel to set
* @param red: red part of color
* @param green: green part of color
* @param blue: blue part of color
*
* @return
* - ESP_OK: Set RGB for a specific pixel successfully
* - ESP_ERR_INVALID_ARG: Set RGB for a specific pixel failed because of invalid parameters
* - ESP_FAIL: Set RGB for a specific pixel failed because other error occurred
*/
esp_err_t (*set_pixel)(led_strip_t *strip, uint32_t index, uint32_t red, uint32_t green, uint32_t blue);
/**
* @brief Refresh memory colors to LEDs
*
* @param strip: LED strip
* @param timeout_ms: timeout value for refreshing task
*
* @return
* - ESP_OK: Refresh successfully
* - ESP_FAIL: Refresh failed because some other error occurred
*
* @note:
* After updating the LED colors in the memory, a following invocation of this API is needed to flush colors to strip.
*/
esp_err_t (*refresh)(led_strip_t *strip);
/**
* @brief Clear LED strip (turn off all LEDs)
*
* @param strip: LED strip
* @param timeout_ms: timeout value for clearing task
*
* @return
* - ESP_OK: Clear LEDs successfully
* - ESP_FAIL: Clear LEDs failed because some other error occurred
*/
esp_err_t (*clear)(led_strip_t *strip);
/**
* @brief Free LED strip resources
*
* @param strip: LED strip
*
* @return
* - ESP_OK: Free resources successfully
* - ESP_FAIL: Free resources failed because error occurred
*/
esp_err_t (*del)(led_strip_t *strip);
};
#ifdef __cplusplus
}
#endif

View File

@@ -1,35 +0,0 @@
/*
* SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include "esp_log.h"
#include "esp_check.h"
#include "led_strip.h"
#include "led_strip_interface.h"
static const char *TAG = "led_strip";
esp_err_t led_strip_set_pixel(led_strip_handle_t strip, uint32_t index, uint32_t red, uint32_t green, uint32_t blue)
{
ESP_RETURN_ON_FALSE(strip, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
return strip->set_pixel(strip, index, red, green, blue);
}
esp_err_t led_strip_refresh(led_strip_handle_t strip)
{
ESP_RETURN_ON_FALSE(strip, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
return strip->refresh(strip);
}
esp_err_t led_strip_clear(led_strip_handle_t strip)
{
ESP_RETURN_ON_FALSE(strip, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
return strip->clear(strip);
}
esp_err_t led_strip_del(led_strip_handle_t strip)
{
ESP_RETURN_ON_FALSE(strip, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
return strip->del(strip);
}

View File

@@ -1,112 +0,0 @@
/*
* SPDX-FileCopyrightText: 2019-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <stdlib.h>
#include <string.h>
#include <sys/cdefs.h>
#include "esp_log.h"
#include "esp_check.h"
#include "driver/rmt_tx.h"
#include "led_strip.h"
#include "led_strip_interface.h"
#include "led_strip_rmt_encoder.h"
#define LED_SRIP_RMT_RESOLUTION 10000000 // 10MHz resolution
static const char *TAG = "led_strip_rmt";
typedef struct {
led_strip_t base;
rmt_channel_handle_t rmt_chan;
rmt_encoder_handle_t strip_encoder;
uint32_t strip_len;
uint8_t pixel_buf[];
} led_strip_rmt_obj;
static esp_err_t led_strip_rmt_set_pixel(led_strip_t *strip, uint32_t index, uint32_t red, uint32_t green, uint32_t blue)
{
led_strip_rmt_obj *rmt_strip = __containerof(strip, led_strip_rmt_obj, base);
ESP_RETURN_ON_FALSE(index < rmt_strip->strip_len, ESP_ERR_INVALID_ARG, TAG, "index out of maximum number of LEDs");
uint32_t start = index * 3;
// In thr order of GRB, as LED strip like WS2812 sends out pixels in this order
rmt_strip->pixel_buf[start + 0] = green & 0xFF;
rmt_strip->pixel_buf[start + 1] = red & 0xFF;
rmt_strip->pixel_buf[start + 2] = blue & 0xFF;
return ESP_OK;
}
static esp_err_t led_strip_rmt_refresh(led_strip_t *strip)
{
led_strip_rmt_obj *rmt_strip = __containerof(strip, led_strip_rmt_obj, base);
rmt_transmit_config_t tx_conf = {
.loop_count = 0,
};
ESP_RETURN_ON_ERROR(rmt_transmit(rmt_strip->rmt_chan, rmt_strip->strip_encoder, rmt_strip->pixel_buf,
rmt_strip->strip_len * 3, &tx_conf), TAG, "transmit pixels by RMT failed");
ESP_RETURN_ON_ERROR(rmt_tx_wait_all_done(rmt_strip->rmt_chan, -1), TAG, "flush RMT channel failed");
return ESP_OK;
}
static esp_err_t led_strip_rmt_clear(led_strip_t *strip)
{
led_strip_rmt_obj *rmt_strip = __containerof(strip, led_strip_rmt_obj, base);
// Write zero to turn off all leds
memset(rmt_strip->pixel_buf, 0, rmt_strip->strip_len * 3);
return led_strip_rmt_refresh(strip);
}
static esp_err_t led_strip_rmt_del(led_strip_t *strip)
{
led_strip_rmt_obj *rmt_strip = __containerof(strip, led_strip_rmt_obj, base);
ESP_RETURN_ON_ERROR(rmt_disable(rmt_strip->rmt_chan), TAG, "disable RMT channel failed");
ESP_RETURN_ON_ERROR(rmt_del_channel(rmt_strip->rmt_chan), TAG, "delete RMT channel failed");
ESP_RETURN_ON_ERROR(rmt_del_encoder(rmt_strip->strip_encoder), TAG, "delete strip encoder failed");
free(rmt_strip);
return ESP_OK;
}
esp_err_t led_strip_new_rmt_device(const led_strip_config_t *config, led_strip_handle_t *ret_strip)
{
led_strip_rmt_obj *rmt_strip = NULL;
esp_err_t ret = ESP_OK;
ESP_GOTO_ON_FALSE(config && ret_strip, ESP_ERR_INVALID_ARG, err, TAG, "invalid argument");
rmt_strip = calloc(1, sizeof(led_strip_rmt_obj) + config->max_leds * 3);
ESP_GOTO_ON_FALSE(rmt_strip, ESP_ERR_NO_MEM, err, TAG, "no mem for rmt strip");
rmt_tx_channel_config_t rmt_chan_config = {
.clk_src = RMT_CLK_SRC_DEFAULT,
.gpio_num = config->strip_gpio_num,
.mem_block_symbols = 64,
.resolution_hz = LED_SRIP_RMT_RESOLUTION,
.trans_queue_depth = 4,
};
ESP_GOTO_ON_ERROR(rmt_new_tx_channel(&rmt_chan_config, &rmt_strip->rmt_chan), err, TAG, "create RMT TX channel failed");
led_strip_encoder_config_t strip_encoder_conf = {
.resolution = LED_SRIP_RMT_RESOLUTION,
};
ESP_GOTO_ON_ERROR(rmt_new_led_strip_encoder(&strip_encoder_conf, &rmt_strip->strip_encoder), err, TAG, "create LED strip encoder failed");
ESP_GOTO_ON_ERROR(rmt_enable(rmt_strip->rmt_chan), err, TAG, "enable RMT channel failed");
rmt_strip->strip_len = config->max_leds;
rmt_strip->base.set_pixel = led_strip_rmt_set_pixel;
rmt_strip->base.refresh = led_strip_rmt_refresh;
rmt_strip->base.clear = led_strip_rmt_clear;
rmt_strip->base.del = led_strip_rmt_del;
*ret_strip = &rmt_strip->base;
return ESP_OK;
err:
if (rmt_strip) {
if (rmt_strip->rmt_chan) {
rmt_del_channel(rmt_strip->rmt_chan);
}
if (rmt_strip->strip_encoder) {
rmt_del_encoder(rmt_strip->strip_encoder);
}
free(rmt_strip);
}
return ret;
}

View File

@@ -1,124 +0,0 @@
/*
* SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include "esp_check.h"
#include "led_strip_rmt_encoder.h"
static const char *TAG = "led_encoder";
typedef struct {
rmt_encoder_t base;
rmt_encoder_t *bytes_encoder;
rmt_encoder_t *copy_encoder;
int state;
rmt_symbol_word_t reset_code;
} rmt_led_strip_encoder_t;
static size_t rmt_encode_led_strip(rmt_encoder_t *encoder, rmt_channel_handle_t channel, const void *primary_data, size_t data_size, rmt_encode_state_t *ret_state)
{
rmt_led_strip_encoder_t *led_encoder = __containerof(encoder, rmt_led_strip_encoder_t, base);
rmt_encoder_handle_t bytes_encoder = led_encoder->bytes_encoder;
rmt_encoder_handle_t copy_encoder = led_encoder->copy_encoder;
rmt_encode_state_t session_state = 0;
rmt_encode_state_t state = 0;
size_t encoded_symbols = 0;
switch (led_encoder->state) {
case 0: // send RGB data
encoded_symbols += bytes_encoder->encode(bytes_encoder, channel, primary_data, data_size, &session_state);
if (session_state & RMT_ENCODING_COMPLETE) {
led_encoder->state = 1; // switch to next state when current encoding session finished
}
if (session_state & RMT_ENCODING_MEM_FULL) {
state |= RMT_ENCODING_MEM_FULL;
goto out; // yield if there's no free space for encoding artifacts
}
// fall-through
case 1: // send reset code
encoded_symbols += copy_encoder->encode(copy_encoder, channel, &led_encoder->reset_code,
sizeof(led_encoder->reset_code), &session_state);
if (session_state & RMT_ENCODING_COMPLETE) {
led_encoder->state = 0; // back to the initial encoding session
state |= RMT_ENCODING_COMPLETE;
}
if (session_state & RMT_ENCODING_MEM_FULL) {
state |= RMT_ENCODING_MEM_FULL;
goto out; // yield if there's no free space for encoding artifacts
}
}
out:
*ret_state = state;
return encoded_symbols;
}
static esp_err_t rmt_del_led_strip_encoder(rmt_encoder_t *encoder)
{
rmt_led_strip_encoder_t *led_encoder = __containerof(encoder, rmt_led_strip_encoder_t, base);
rmt_del_encoder(led_encoder->bytes_encoder);
rmt_del_encoder(led_encoder->copy_encoder);
free(led_encoder);
return ESP_OK;
}
static esp_err_t rmt_led_strip_encoder_reset(rmt_encoder_t *encoder)
{
rmt_led_strip_encoder_t *led_encoder = __containerof(encoder, rmt_led_strip_encoder_t, base);
rmt_encoder_reset(led_encoder->bytes_encoder);
rmt_encoder_reset(led_encoder->copy_encoder);
led_encoder->state = 0;
return ESP_OK;
}
esp_err_t rmt_new_led_strip_encoder(const led_strip_encoder_config_t *config, rmt_encoder_handle_t *ret_encoder)
{
esp_err_t ret = ESP_OK;
rmt_led_strip_encoder_t *led_encoder = NULL;
ESP_GOTO_ON_FALSE(config && ret_encoder, ESP_ERR_INVALID_ARG, err, TAG, "invalid argument");
led_encoder = calloc(1, sizeof(rmt_led_strip_encoder_t));
ESP_GOTO_ON_FALSE(led_encoder, ESP_ERR_NO_MEM, err, TAG, "no mem for led strip encoder");
led_encoder->base.encode = rmt_encode_led_strip;
led_encoder->base.del = rmt_del_led_strip_encoder;
led_encoder->base.reset = rmt_led_strip_encoder_reset;
// different led strip might have its own timing requirements, following parameter is for WS2812
rmt_bytes_encoder_config_t bytes_encoder_config = {
.bit0 = {
.level0 = 1,
.duration0 = 0.3 * config->resolution / 1000000, // T0H=0.3us
.level1 = 0,
.duration1 = 0.9 * config->resolution / 1000000, // T0L=0.9us
},
.bit1 = {
.level0 = 1,
.duration0 = 0.9 * config->resolution / 1000000, // T1H=0.9us
.level1 = 0,
.duration1 = 0.3 * config->resolution / 1000000, // T1L=0.3us
},
.flags.msb_first = 1 // WS2812 transfer bit order: G7...G0R7...R0B7...B0
};
ESP_GOTO_ON_ERROR(rmt_new_bytes_encoder(&bytes_encoder_config, &led_encoder->bytes_encoder), err, TAG, "create bytes encoder failed");
rmt_copy_encoder_config_t copy_encoder_config = {};
ESP_GOTO_ON_ERROR(rmt_new_copy_encoder(&copy_encoder_config, &led_encoder->copy_encoder), err, TAG, "create copy encoder failed");
uint32_t reset_ticks = config->resolution / 1000000 * 50 / 2; // reset code duration defaults to 50us
led_encoder->reset_code = (rmt_symbol_word_t) {
.level0 = 0,
.duration0 = reset_ticks,
.level1 = 0,
.duration1 = reset_ticks,
};
*ret_encoder = &led_encoder->base;
return ESP_OK;
err:
if (led_encoder) {
if (led_encoder->bytes_encoder) {
rmt_del_encoder(led_encoder->bytes_encoder);
}
if (led_encoder->copy_encoder) {
rmt_del_encoder(led_encoder->copy_encoder);
}
free(led_encoder);
}
return ret;
}

View File

@@ -1,36 +0,0 @@
/*
* SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once
#include <stdint.h>
#include "driver/rmt_encoder.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Type of led strip encoder configuration
*/
typedef struct {
uint32_t resolution; /*!< Encoder resolution, in Hz */
} led_strip_encoder_config_t;
/**
* @brief Create RMT encoder for encoding LED strip pixels into RMT symbols
*
* @param[in] config Encoder configuration
* @param[out] ret_encoder Returned encoder handle
* @return
* - ESP_ERR_INVALID_ARG for any invalid arguments
* - ESP_ERR_NO_MEM out of memory when creating led strip encoder
* - ESP_OK if creating encoder successfully
*/
esp_err_t rmt_new_led_strip_encoder(const led_strip_encoder_config_t *config, rmt_encoder_handle_t *ret_encoder);
#ifdef __cplusplus
}
#endif

View File

@@ -2,7 +2,5 @@
# CMakeLists in this exact order for cmake to work correctly
cmake_minimum_required(VERSION 3.16)
set(EXTRA_COMPONENT_DIRS $ENV{IDF_PATH}/examples/common_components/led_strip)
include($ENV{IDF_PATH}/tools/cmake/project.cmake)
project(blink)

View File

@@ -5,9 +5,9 @@
(See the README.md file in the upper level 'examples' directory for more information about examples.)
This example demonstrates how to blink a LED using GPIO or RMT for the addressable LED, i.e. [WS2812](http://www.world-semi.com/Certifications/WS2812B.html).
This example demonstrates how to blink a LED using GPIO or using the [led_strip](https://components.espressif.com/component/espressif/led_strip) component for the addressable LED, i.e. [WS2812](http://www.world-semi.com/Certifications/WS2812B.html).
See the RMT examples in the [RMT Peripheral](../../peripherals/rmt) for more information about how to use it.
The `led_strip` is installed via [component manager](main/idf_component.yml).
## How to Use Example
@@ -37,7 +37,7 @@ Open the project configuration menu (`idf.py menuconfig`).
In the `Example Configuration` menu:
* Select the LED type in the `Blink LED type` option.
* Use `GPIO` for regular LED blink.
* Use `GPIO` for regular LED blink.
* Set the GPIO number used for the signal in the `Blink GPIO number` option.
* Set the blinking period in the `Blink period in ms` option.
@@ -53,7 +53,7 @@ See the [Getting Started Guide](https://docs.espressif.com/projects/esp-idf/en/l
As you run the example, you will see the LED blinking, according to the previously defined period. For the addressable LED, you can also change the LED color by setting the `led_strip_set_pixel(led_strip, 0, 16, 16, 16);` (LED Strip, Pixel Number, Red, Green, Blue) with values from 0 to 255 in the [source file](main/blink_example_main.c).
```
```text
I (315) example: Example configured to blink addressable LED!
I (325) example: Turning the LED OFF!
I (1325) example: Turning the LED ON!

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