driver: remove -Wno-format flag

pull/9553/head
morris 2022-08-04 13:08:48 +08:00
rodzic c25c254666
commit d91c8759c0
78 zmienionych plików z 132 dodań i 174 usunięć

Wyświetl plik

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

Wyświetl plik

@ -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")

Wyświetl plik

@ -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

Wyświetl plik

@ -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);
}

Wyświetl plik

@ -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) {

Wyświetl plik

@ -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);

Wyświetl plik

@ -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) {

Wyświetl plik

@ -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;
@ -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;
}

Wyświetl plik

@ -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

Wyświetl plik

@ -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);

Wyświetl plik

@ -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);

Wyświetl plik

@ -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);

Wyświetl plik

@ -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;
}

Wyświetl plik

@ -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;
}

Wyświetl plik

@ -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;
}

Wyświetl plik

@ -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);

Wyświetl plik

@ -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;

Wyświetl plik

@ -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

Wyświetl plik

@ -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;
}

Wyświetl plik

@ -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);
}

Wyświetl plik

@ -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);
}

Wyświetl plik

@ -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:

Wyświetl plik

@ -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;

Wyświetl plik

@ -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;

Wyświetl plik

@ -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);

Wyświetl plik

@ -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;

Wyświetl plik

@ -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) {

Wyświetl plik

@ -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")

Wyświetl plik

@ -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;
}
}

Wyświetl plik

@ -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")

Wyświetl plik

@ -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);
}

Wyświetl plik

@ -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")

Wyświetl plik

@ -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"
@ -110,7 +111,7 @@ 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]);
@ -225,12 +226,12 @@ TEST_CASE("mcpwm_capture_timer_sync_phase_lock", "[mcpwm]")
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_del_capture_channel(cap_channel));
TEST_ESP_OK(mcpwm_del_capture_timer(cap_timer));

Wyświetl plik

@ -3,6 +3,7 @@
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <inttypes.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "unity.h"
@ -101,7 +102,7 @@ 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);

Wyświetl plik

@ -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"
@ -78,7 +79,7 @@ TEST_CASE("mcpwm_capture_iram_safe", "[mcpwm]")
printf("disable cache, simulate GPIO capture signal\r\n");
test_mcpwm_capture_gpio_simulate(cap_gpio);
printf("capture value: Pos=%u, Neg=%u\r\n", cap_value[0], cap_value[1]);
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]);

Wyświetl plik

@ -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)

Wyświetl plik

@ -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 */

Wyświetl plik

@ -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
@ -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:

Wyświetl plik

@ -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

Wyświetl plik

@ -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;
}

Wyświetl plik

@ -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")

Wyświetl plik

@ -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");

Wyświetl plik

@ -1,3 +1,2 @@
idf_component_register(SRCS "continuous_read_main.c"
INCLUDE_DIRS ".")
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

Wyświetl plik

@ -133,7 +133,7 @@ void app_main(void)
while (1) {
ret = adc_continuous_read(handle, result, EXAMPLE_READ_LEN, &ret_num, 0);
if (ret == ESP_OK) {
ESP_LOGI("TASK", "ret is %x, ret_num is %d", ret, ret_num);
ESP_LOGI("TASK", "ret is %x, ret_num is %"PRIu32, ret, ret_num);
for (int i = 0; i < ret_num; i += SOC_ADC_DIGI_RESULT_BYTES) {
adc_digi_output_data_t *p = (void*)&result[i];
#if CONFIG_IDF_TARGET_ESP32

Wyświetl plik

@ -1,3 +1,2 @@
idf_component_register(SRCS "gpio_example_main.c"
INCLUDE_DIRS ".")
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

Wyświetl plik

@ -9,6 +9,7 @@
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include <inttypes.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/queue.h"
@ -55,7 +56,7 @@ static void gpio_task_example(void* arg)
uint32_t io_num;
for(;;) {
if(xQueueReceive(gpio_evt_queue, &io_num, portMAX_DELAY)) {
printf("GPIO[%d] intr, val: %d\n", io_num, gpio_get_level(io_num));
printf("GPIO[%"PRIu32"] intr, val: %d\n", io_num, gpio_get_level(io_num));
}
}
}
@ -107,7 +108,7 @@ void app_main(void)
//hook isr handler for specific gpio pin again
gpio_isr_handler_add(GPIO_INPUT_IO_0, gpio_isr_handler, (void*) GPIO_INPUT_IO_0);
printf("Minimum free heap size: %d bytes\n", esp_get_minimum_free_heap_size());
printf("Minimum free heap size: %"PRIu32" bytes\n", esp_get_minimum_free_heap_size());
int cnt = 0;
while(1) {

Wyświetl plik

@ -5,4 +5,3 @@ idf_component_register(SRCS "${component_srcs}"
PRIV_INCLUDE_DIRS ""
PRIV_REQUIRES "driver"
REQUIRES "")
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

Wyświetl plik

@ -1,16 +1,8 @@
// Copyright 2020 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
/*
* SPDX-FileCopyrightText: 2020-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <stdlib.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
@ -67,7 +59,7 @@ static void matrix_kbd_debounce_timer_callback(TimerHandle_t xTimer)
uint32_t row_out = dedic_gpio_bundle_read_out(mkbd->row_bundle);
uint32_t col_in = dedic_gpio_bundle_read_in(mkbd->col_bundle);
row_out = (~row_out) & ((1 << mkbd->nr_row_gpios) - 1);
ESP_LOGD(TAG, "row_out=%x, col_in=%x", row_out, col_in);
ESP_LOGD(TAG, "row_out=%"PRIx32", col_in=%"PRIx32, row_out, col_in);
int row = -1;
int col = -1;
uint32_t key_code = 0;

Wyświetl plik

@ -1,3 +1,2 @@
idf_component_register(SRCS "matrix_keyboard_example_main.c"
INCLUDE_DIRS "")
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

Wyświetl plik

@ -21,10 +21,10 @@ esp_err_t example_matrix_kbd_event_handler(matrix_kbd_handle_t mkbd_handle, matr
uint32_t key_code = (uint32_t)event_data;
switch (event) {
case MATRIX_KBD_EVENT_DOWN:
ESP_LOGI(TAG, "press event, key code = %04x", key_code);
ESP_LOGI(TAG, "press event, key code = %04"PRIx32, key_code);
break;
case MATRIX_KBD_EVENT_UP:
ESP_LOGI(TAG, "release event, key code = %04x", key_code);
ESP_LOGI(TAG, "release event, key code = %04"PRIx32, key_code);
break;
}
return ESP_OK;

Wyświetl plik

@ -1,3 +1,2 @@
idf_component_register(SRCS "i2c_example_main.c"
INCLUDE_DIRS ".")
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")
INCLUDE_DIRS ".")

Wyświetl plik

@ -213,7 +213,7 @@ static void disp_buf(uint8_t *buf, int len)
static void i2c_test_task(void *arg)
{
int ret;
uint32_t task_idx = (uint32_t)arg;
int task_idx = (int)arg;
#if SOC_I2C_NUM > 1
int i = 0;
uint8_t *data = (uint8_t *)malloc(DATA_LENGTH);

Wyświetl plik

@ -1,4 +1,3 @@
idf_component_register(SRCS "i2ctools_example_main.c"
"cmd_i2ctools.c"
INCLUDE_DIRS ".")
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")
INCLUDE_DIRS ".")

Wyświetl plik

@ -380,7 +380,7 @@ static int do_i2cdump_cmd(int argc, char **argv)
} else if ((block[k] & 0xff) < 32 || (block[k] & 0xff) >= 127) {
printf("?");
} else {
printf("%c", block[k] & 0xff);
printf("%c", (char)(block[k] & 0xff));
}
}
printf("\r\n");

Wyświetl plik

@ -1,3 +1,2 @@
idf_component_register(SRCS "app_main.c"
INCLUDE_DIRS ".")
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

Wyświetl plik

@ -101,7 +101,7 @@ void example_erase_flash(void)
data_partition = esp_partition_find_first(ESP_PARTITION_TYPE_DATA,
ESP_PARTITION_SUBTYPE_DATA_FAT, PARTITION_NAME);
if (data_partition != NULL) {
printf("partiton addr: 0x%08x; size: %d; label: %s\n", data_partition->address, data_partition->size, data_partition->label);
printf("partiton addr: 0x%08"PRIx32"; size: %"PRIu32"; label: %s\n", data_partition->address, data_partition->size, data_partition->label);
}
printf("Erase size: %d Bytes\n", FLASH_ERASE_SIZE);
ESP_ERROR_CHECK(esp_partition_erase_range(data_partition, 0, FLASH_ERASE_SIZE));
@ -209,7 +209,7 @@ void example_i2s_adc_dac(void*arg)
data_partition = esp_partition_find_first(ESP_PARTITION_TYPE_DATA,
ESP_PARTITION_SUBTYPE_DATA_FAT, PARTITION_NAME);
if (data_partition != NULL) {
printf("partiton addr: 0x%08x; size: %d; label: %s\n", data_partition->address, data_partition->size, data_partition->label);
printf("partiton addr: 0x%08"PRIx32"; size: %"PRIu32"; label: %s\n", data_partition->address, data_partition->size, data_partition->label);
} else {
ESP_LOGE(TAG, "Partition error: can't find partition name: %s\n", PARTITION_NAME);
vTaskDelete(NULL);
@ -288,7 +288,7 @@ void adc_read_task(void* arg)
uint32_t voltage;
vTaskDelay(200 / portTICK_PERIOD_MS);
esp_adc_cal_get_voltage(ADC1_TEST_CHANNEL, &characteristics, &voltage);
ESP_LOGI(TAG, "%d mV", voltage);
ESP_LOGI(TAG, "%"PRIu32" mV", voltage);
}
}

Wyświetl plik

@ -1,4 +1,2 @@
idf_component_register(SRCS "rgb_lcd_example_main.c" "lvgl_demo_ui.c"
INCLUDE_DIRS ".")
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

Wyświetl plik

@ -1,3 +1,2 @@
idf_component_register(SRCS "mcpwm_bldc_hall_control_example_main.c"
INCLUDE_DIRS ".")
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

Wyświetl plik

@ -344,7 +344,7 @@ void app_main(void)
if (hall_sensor_value >= 1 && hall_sensor_value <= 6) {
s_hall_actions[hall_sensor_value](generators);
} else {
ESP_LOGE(TAG, "invalid bldc phase, wrong hall sensor value:%d", hall_sensor_value);
ESP_LOGE(TAG, "invalid bldc phase, wrong hall sensor value:%"PRIu32, hall_sensor_value);
}
ulTaskNotifyTake(pdTRUE, portMAX_DELAY);
}

Wyświetl plik

@ -1,3 +1,2 @@
idf_component_register(SRCS "mcpwm_capture_hc_sr04.c"
INCLUDE_DIRS ".")
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

Wyświetl plik

@ -1,3 +1,2 @@
idf_component_register(SRCS "app_main.c"
INCLUDE_DIRS ".")
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

Wyświetl plik

@ -307,7 +307,7 @@ static esp_err_t get_intr(essl_handle_t handle, uint32_t* out_raw, uint32_t* out
if (ret != ESP_OK) return ret;
ret = essl_clear_intr(handle, *out_raw, TIMEOUT_MAX);
if (ret != ESP_OK) return ret;
ESP_LOGD(TAG, "intr: %08X", *out_raw);
ESP_LOGD(TAG, "intr: %08"PRIX32, *out_raw);
return ESP_OK;
}

Wyświetl plik

@ -6,5 +6,3 @@ set(srcs "pretty_effect.c"
idf_component_register(SRCS ${srcs}
INCLUDE_DIRS "."
EMBED_FILES image.jpg)
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

Wyświetl plik

@ -9,6 +9,7 @@
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <inttypes.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "esp_system.h"
@ -272,7 +273,7 @@ void lcd_init(spi_device_handle_t spi)
int lcd_detected_type = 0;
int lcd_type;
printf("LCD ID: %08X\n", lcd_id);
printf("LCD ID: %08"PRIx32"\n", lcd_id);
if ( lcd_id == 0 ) {
//zero, ili
lcd_detected_type = LCD_TYPE_ILI;

Wyświetl plik

@ -1,3 +1,2 @@
idf_component_register(SRCS "app_main.c"
INCLUDE_DIRS ".")
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

Wyświetl plik

@ -1,3 +1,2 @@
idf_component_register(SRCS "app_main.c"
INCLUDE_DIRS ".")
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

Wyświetl plik

@ -207,8 +207,8 @@ void app_main(void)
ESP_ERROR_CHECK(get_slave_max_buf_size(spi, &slave_max_tx_buf_size, &slave_max_rx_buf_size));
uint32_t rx_buf_size = slave_max_tx_buf_size;
printf("\n\n---------SLAVE INFO---------\n\n");
printf("Slave MAX Send Buffer Size: %d\n", slave_max_tx_buf_size);
printf("Slave MAX Receive Buffer Size: %d\n", slave_max_rx_buf_size);
printf("Slave MAX Send Buffer Size: %"PRIu32"\n", slave_max_tx_buf_size);
printf("Slave MAX Receive Buffer Size: %"PRIu32"\n", slave_max_rx_buf_size);
uint8_t *recv_buf = heap_caps_calloc(1, rx_buf_size, MALLOC_CAP_DMA);
if (!recv_buf) {
@ -245,7 +245,7 @@ void app_main(void)
uint32_t size_can_be_read = get_slave_tx_buf_size(spi) - size_has_read;
if (size_can_be_read > rx_buf_size) {
ESP_LOGW(TAG, "Slave is going to send buffer(%d Bytes) larger than pre-negotiated MAX size", size_can_be_read);
ESP_LOGW(TAG, "Slave is going to send buffer(%"PRIu32" Bytes) larger than pre-negotiated MAX size", size_can_be_read);
/**
* NOTE:
* In this condition, Master should still increase its counter (``size_has_read``) by the size that Slave has loaded,
@ -277,7 +277,7 @@ void app_main(void)
//Prepare your TX transaction in your own way. Here is an example.
//You can set any size to send (shorter, longer or equal to the Slave Max RX buf size), Slave can get the actual length by ``trans_len`` member of ``spi_slave_hd_data_t``
uint32_t actual_tx_size = (rand() % (slave_max_rx_buf_size - TX_SIZE_MIN + 1)) + TX_SIZE_MIN;
snprintf((char *)send_buf, slave_max_rx_buf_size, "this is master's transaction %d", tx_trans_id);
snprintf((char *)send_buf, slave_max_rx_buf_size, "this is master's transaction %"PRIu32, tx_trans_id);
for (int i = 0; i < num_to_send; i++) {
ESP_ERROR_CHECK(essl_spi_wrdma(spi, send_buf, actual_tx_size, -1, 0));

Wyświetl plik

@ -1,3 +1,2 @@
idf_component_register(SRCS "app_main.c"
INCLUDE_DIRS ".")
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

Wyświetl plik

@ -156,7 +156,7 @@ static bool get_tx_data(uint8_t *data, uint32_t max_len, uint32_t *out_len)
return false;
}
snprintf((char *)data, *out_len, "Transaction No.%d from slave, length: %d", s_tx_data_id, *out_len);
snprintf((char *)data, *out_len, "Transaction No.%"PRIu32" from slave, length: %"PRIu32, s_tx_data_id, *out_len);
s_tx_data_id++;
return true;
}

Wyświetl plik

@ -1,3 +1,2 @@
idf_component_register(SRCS "temp_sensor_main.c"
INCLUDE_DIRS ".")
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")
INCLUDE_DIRS ".")

Wyświetl plik

@ -1,3 +1,2 @@
idf_component_register(SRCS "twai_network_example_listen_only_main.c"
INCLUDE_DIRS ".")
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

Wyświetl plik

@ -78,7 +78,7 @@ static void twai_receive_task(void *arg)
for (int i = 0; i < rx_msg.data_length_code; i++) {
data |= (rx_msg.data[i] << (i * 8));
}
ESP_LOGI(EXAMPLE_TAG, "Received data value %d", data);
ESP_LOGI(EXAMPLE_TAG, "Received data value %"PRIu32, data);
} else if (rx_msg.identifier == ID_MASTER_STOP_CMD) {
ESP_LOGI(EXAMPLE_TAG, "Received master stop command");
} else if (rx_msg.identifier == ID_SLAVE_STOP_RESP) {

Wyświetl plik

@ -1,3 +1,2 @@
idf_component_register(SRCS "twai_network_example_master_main.c"
INCLUDE_DIRS ".")
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

Wyświetl plik

@ -109,7 +109,7 @@ static void twai_receive_task(void *arg)
for (int i = 0; i < rx_msg.data_length_code; i++) {
data |= (rx_msg.data[i] << (i * 8));
}
ESP_LOGI(EXAMPLE_TAG, "Received data value %d", data);
ESP_LOGI(EXAMPLE_TAG, "Received data value %"PRIu32, data);
data_msgs_rec ++;
}
}

Wyświetl plik

@ -1,3 +1,2 @@
idf_component_register(SRCS "twai_network_example_slave_main.c"
INCLUDE_DIRS ".")
target_compile_options(${COMPONENT_LIB} PRIVATE "-Wno-format")

Wyświetl plik

@ -146,7 +146,7 @@ static void twai_transmit_task(void *arg)
data_message.data[i] = (sensor_data >> (i * 8)) & 0xFF;
}
twai_transmit(&data_message, portMAX_DELAY);
ESP_LOGI(EXAMPLE_TAG, "Transmitted data value %d", sensor_data);
ESP_LOGI(EXAMPLE_TAG, "Transmitted data value %"PRIu32, sensor_data);
vTaskDelay(pdMS_TO_TICKS(DATA_PERIOD_MS));
if (xSemaphoreTake(stop_data_sem, 0) == pdTRUE) {
break;

Wyświetl plik

@ -1728,7 +1728,6 @@ examples/peripherals/adc/single_read/adc2/main/adc2_example_main.c
examples/peripherals/gpio/generic_gpio/example_test.py
examples/peripherals/gpio/generic_gpio/main/gpio_example_main.c
examples/peripherals/gpio/matrix_keyboard/components/matrix_keyboard/include/matrix_keyboard.h
examples/peripherals/gpio/matrix_keyboard/components/matrix_keyboard/src/matrix_keyboard.c
examples/peripherals/gpio/matrix_keyboard/main/matrix_keyboard_example_main.c
examples/peripherals/i2c/i2c_simple/main/i2c_simple_main.c
examples/peripherals/i2c/i2c_tools/example_test.py

Wyświetl plik

@ -24,9 +24,6 @@ components/esp_rom/include/esp32s2/rom/rsa_pss.h
components/esp_common/include/esp_private/
components/esp32/include/esp32/brownout.h
components/esp32/include/esp32/cache_err_int.h
# LWIP: sockets.h uses #include_next<>, which doesn't work correctly with the checker
# memp_std.h is supposed to be included multiple times with different settings
components/lwip/lwip/src/include/lwip/priv/memp_std.h
@ -115,9 +112,6 @@ components/esp_rom/include/esp32s2/rom/efuse.h
components/esp_rom/include/esp32s3/rom/rtc.h
components/esp_rom/include/esp32h2/rom/rtc.h
components/esp_rom/include/esp32c2/rom/rtc.h
components/esp32/include/esp32/dport_access.h
components/esp32/include/rom/sha.h
components/esp32/include/rom/secure_boot.h
components/esp_ringbuf/include/freertos/ringbuf.h
components/esp_wifi/include/esp_wifi_crypto_types.h
components/esp_wifi/include/esp_coexist_internal.h
@ -130,7 +124,6 @@ components/esp_netif/include/esp_netif_sta_list.h
components/esp_netif/include/esp_netif_defaults.h
components/esp_netif/include/esp_netif_net_stack.h
components/esp_netif/include/esp_netif_ppp.h
components/console/linenoise/linenoise.h
components/protocomm/include/transports/protocomm_httpd.h
components/fatfs/src/diskio.h
components/fatfs/diskio/diskio_sdmmc.h
@ -162,8 +155,3 @@ components/espcoredump/include/port/xtensa/esp_core_dump_summary_port.h
components/riscv/include/esp_private/panic_reason.h
components/riscv/include/riscv/interrupt.h
components/riscv/include/riscv/rvruntime-frames.h
### To be fixed: files which don't compile for esp32c2 target:
components/efuse/esp32c2/include/esp_efuse_table.h