Merge branch 'feature/update-toolchain-to-esp-14.2.0_20240903' into 'master'

feat(tools): update toolchain version to esp-14.2.0_20240906

Closes IDFGH-13033, IDFGH-13355, and IDFGH-13360

See merge request espressif/esp-idf!33295
This commit is contained in:
Alexey Lapshin 2024-09-09 14:22:47 +08:00
commit 599c14d8f0
47 changed files with 284 additions and 168 deletions

View File

@ -175,6 +175,10 @@ if(CONFIG_COMPILER_DISABLE_GCC13_WARNINGS)
"-Wno-dangling-reference")
endif()
if(CONFIG_COMPILER_DISABLE_GCC14_WARNINGS)
list(APPEND compile_options "-Wno-calloc-transposed-args")
endif()
if(CONFIG_COMPILER_DISABLE_DEFAULT_ERRORS)
if(NOT CMAKE_C_COMPILER_ID MATCHES "Clang")
idf_build_replace_option_from_property(COMPILE_OPTIONS "-Werror" "-Werror=all")

View File

@ -587,6 +587,13 @@ mainmenu "Espressif IoT Development Framework Configuration"
Enable this option if use GCC 13 or newer, and want to disable warnings which don't appear with
GCC 12.
config COMPILER_DISABLE_GCC14_WARNINGS
bool "Disable new warnings introduced in GCC 14"
default "n"
help
Enable this option if use GCC 14 or newer, and want to disable warnings which don't appear with
GCC 13.
config COMPILER_DUMP_RTL_FILES
bool "Dump RTL files during compilation"
help

View File

@ -157,7 +157,7 @@ esp_err_t esp_ota_begin(const esp_partition_t *partition, size_t image_size, esp
}
}
new_entry = (ota_ops_entry_t *) calloc(sizeof(ota_ops_entry_t), 1);
new_entry = (ota_ops_entry_t *) calloc(1, sizeof(ota_ops_entry_t));
if (new_entry == NULL) {
return ESP_ERR_NO_MEM;
}

View File

@ -2385,7 +2385,12 @@ void bta_dm_queue_search (tBTA_DM_MSG *p_data)
osi_free(bta_dm_search_cb.p_search_queue);
}
bta_dm_search_cb.p_search_queue = (tBTA_DM_MSG *)osi_malloc(sizeof(tBTA_DM_API_SEARCH));
tBTA_DM_API_SEARCH *search_queue = osi_malloc(sizeof(tBTA_DM_API_SEARCH));
if (search_queue == NULL) {
APPL_TRACE_ERROR("%s: couldn't allocate memory", __func__);
return;
}
bta_dm_search_cb.p_search_queue = (tBTA_DM_MSG *) search_queue;
memcpy(bta_dm_search_cb.p_search_queue, p_data, sizeof(tBTA_DM_API_SEARCH));
}
@ -2406,7 +2411,12 @@ void bta_dm_queue_disc (tBTA_DM_MSG *p_data)
osi_free(bta_dm_search_cb.p_search_queue);
}
bta_dm_search_cb.p_search_queue = (tBTA_DM_MSG *)osi_malloc(sizeof(tBTA_DM_API_DISCOVER));
tBTA_DM_API_DISCOVER *search_queue = osi_malloc(sizeof(tBTA_DM_API_DISCOVER));
if (search_queue == NULL) {
APPL_TRACE_ERROR("%s: couldn't allocate memory", __func__);
return;
}
bta_dm_search_cb.p_search_queue = (tBTA_DM_MSG *)search_queue;
memcpy(bta_dm_search_cb.p_search_queue, p_data, sizeof(tBTA_DM_API_DISCOVER));
}
#endif ///SDP_INCLUDED == TRUE

View File

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2015-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -11,6 +11,7 @@ This header contains various general purpose helper macros used across ESP-IDF
*/
#include <assert.h>
#include "esp_assert.h"
#include "esp_compiler.h"
#ifdef __cplusplus
extern "C" {
@ -51,7 +52,7 @@ extern "C" {
* - __GET_NTH_ARG__() takes args >= N (64) but only expand to Nth one (64th)
* - __RSEQ_N__() is reverse sequential to N to add padding to have Nth
* position is the same as the number of arguments
* - ##__VA_ARGS__ is used to deal with 0 paramerter (swallows comma)
* - ##__VA_ARGS__ is used to deal with 0 parameter (swallows comma)
*/
#ifndef __VA_NARG__
# define __VA_NARG__(...) __NARG__(_0, ##__VA_ARGS__, __RSEQ_N__())
@ -98,6 +99,13 @@ ESP_STATIC_ASSERT(foo(42, 87) == 1, "CHOOSE_MACRO_VA_ARG() result does not match
#undef foo_args
#undef foo_no_args
#define ESP_INFINITE_LOOP() \
do { \
ESP_COMPILER_DIAGNOSTIC_PUSH_IGNORE("-Wanalyzer-infinite-loop") \
while(1); \
ESP_COMPILER_DIAGNOSTIC_POP("-Wanalyzer-infinite-loop") \
} while(1)
#ifdef __cplusplus
}
#endif

View File

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2019-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2019-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -149,17 +149,19 @@ err:
esp_err_t dac_dma_periph_deinit(void)
{
if (!s_ddp) {
return ESP_OK;
}
ESP_RETURN_ON_FALSE(s_ddp->intr_handle == NULL, ESP_ERR_INVALID_STATE, TAG, "The interrupt is not deregistered yet");
ESP_RETURN_ON_ERROR(i2s_platform_release_occupation(I2S_CTLR_HP, DAC_DMA_PERIPH_I2S_NUM), TAG, "Failed to release DAC DMA peripheral");
i2s_ll_enable_intr(s_ddp->periph_dev, I2S_LL_EVENT_TX_EOF | I2S_LL_EVENT_TX_TEOF, false);
if (s_ddp) {
if (s_ddp->use_apll) {
periph_rtc_apll_release();
s_ddp->use_apll = false;
}
free(s_ddp);
s_ddp = NULL;
if (s_ddp->use_apll) {
periph_rtc_apll_release();
s_ddp->use_apll = false;
}
free(s_ddp);
s_ddp = NULL;
return ESP_OK;
}

View File

@ -158,6 +158,7 @@ err:
esp_err_t dac_dma_periph_deinit(void)
{
ESP_RETURN_ON_FALSE(s_ddp != NULL, ESP_ERR_INVALID_STATE, TAG, "DAC DMA peripheral is not initialized");
ESP_RETURN_ON_FALSE(s_ddp->intr_handle == NULL, ESP_ERR_INVALID_STATE, TAG, "The interrupt is not deregistered yet");
if (s_ddp->dma_chan) {
ESP_RETURN_ON_ERROR(spicommon_dma_chan_free(s_ddp->spi_dma_ctx), TAG, "Failed to free dma peripheral channel");

View File

@ -4,6 +4,7 @@
* SPDX-License-Identifier: Apache-2.0
*/
#include "esp_compiler.h"
#include "esp_log.h"
#include "esp_check.h"
#include "esp_memory_utils.h"
@ -606,7 +607,9 @@ static esp_err_t s_spi_slave_hd_setup_priv_trans(spi_host_device_t host, spi_sla
}
}
if (chan == SPI_SLAVE_CHAN_TX) {
ESP_COMPILER_DIAGNOSTIC_PUSH_IGNORE("-Wanalyzer-overlapping-buffers") // TODO IDF-11086
memcpy(priv_trans->aligned_buffer, orig_trans->data, orig_trans->len);
ESP_COMPILER_DIAGNOSTIC_POP("-Wanalyzer-overlapping-buffers")
esp_err_t ret = esp_cache_msync((void *)priv_trans->aligned_buffer, byte_len, ESP_CACHE_MSYNC_FLAG_DIR_C2M);
ESP_RETURN_ON_FALSE(ESP_OK == ret, ESP_ERR_INVALID_STATE, TAG, "mem sync c2m(writeback) fail");
} else {

View File

@ -146,11 +146,13 @@ esp_err_t httpd_register_uri_handler(httpd_handle_t handle,
for (int i = 0; i < hd->config.max_uri_handlers; i++) {
if (hd->hd_calls[i] == NULL) {
ESP_COMPILER_DIAGNOSTIC_PUSH_IGNORE("-Wanalyzer-malloc-leak") // False-positive detection. TODO GCC-366
hd->hd_calls[i] = malloc(sizeof(httpd_uri_t));
if (hd->hd_calls[i] == NULL) {
/* Failed to allocate memory */
return ESP_ERR_HTTPD_ALLOC_MEM;
}
ESP_COMPILER_DIAGNOSTIC_POP("-Wanalyzer-malloc-leak")
/* Copy URI string */
hd->hd_calls[i]->uri = strdup(uri_handler->uri);

View File

@ -55,18 +55,22 @@ static clkout_channel_handle_t* clkout_channel_alloc(soc_clkout_sig_id_t clk_sig
clkout_channel_handle_t *allocated_channel = NULL;
#if SOC_GPIO_CLOCKOUT_BY_IO_MUX
portENTER_CRITICAL(&s_clkout_handle[IONUM_TO_CLKOUT_CHANNEL(gpio_num)].clkout_channel_lock);
if (!s_clkout_handle[IONUM_TO_CLKOUT_CHANNEL(gpio_num)].is_mapped) {
s_clkout_handle[IONUM_TO_CLKOUT_CHANNEL(gpio_num)].is_mapped = true;
allocated_channel = &s_clkout_handle[IONUM_TO_CLKOUT_CHANNEL(gpio_num)];
} else if ((s_clkout_handle[IONUM_TO_CLKOUT_CHANNEL(gpio_num)].mapped_io_bmap & BIT(gpio_num)) &&
(s_clkout_handle[IONUM_TO_CLKOUT_CHANNEL(gpio_num)].mapped_clock == clk_sig)) {
allocated_channel = &s_clkout_handle[IONUM_TO_CLKOUT_CHANNEL(gpio_num)];
int32_t channel_num = IONUM_TO_CLKOUT_CHANNEL(gpio_num);
if (channel_num < 0) {
return NULL;
}
portENTER_CRITICAL(&s_clkout_handle[channel_num].clkout_channel_lock);
if (!s_clkout_handle[channel_num].is_mapped) {
s_clkout_handle[channel_num].is_mapped = true;
allocated_channel = &s_clkout_handle[channel_num];
} else if ((s_clkout_handle[channel_num].mapped_io_bmap & BIT(gpio_num)) &&
(s_clkout_handle[channel_num].mapped_clock == clk_sig)) {
allocated_channel = &s_clkout_handle[channel_num];
}
if (allocated_channel != NULL) {
allocated_channel->channel_id = (clock_out_channel_t)IONUM_TO_CLKOUT_CHANNEL(gpio_num);
allocated_channel->channel_id = (clock_out_channel_t)channel_num;
}
portEXIT_CRITICAL(&s_clkout_handle[IONUM_TO_CLKOUT_CHANNEL(gpio_num)].clkout_channel_lock);
portEXIT_CRITICAL(&s_clkout_handle[channel_num].clkout_channel_lock);
#elif SOC_GPIO_CLOCKOUT_BY_GPIO_MATRIX
for (uint32_t channel = 0; channel < CLKOUT_CHANNEL_MAX; channel++) {
portENTER_CRITICAL(&s_clkout_handle[channel].clkout_channel_lock);

View File

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2015-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2015-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -33,7 +33,7 @@
* This lock is designed to solve the conflicts between SPI devices (used in tasks) and
* the background operations (ISR or cache access).
*
* There are N (device/task) + 1 (BG) acquiring processer candidates that may touch the bus.
* There are N (device/task) + 1 (BG) acquiring processor candidates that may touch the bus.
*
* The core of the lock is a `status` atomic variable, which is always available. No intermediate
* status is allowed. The atomic operations (mainly `atomic_fetch_and`, `atomic_fetch_or`)
@ -49,7 +49,7 @@
* state of devices. Either one of REQ or PENDING being active indicates the device has pending BG
* requests. Reason of having two bits instead of one is in the appendix below.
*
* Acquiring processer means the current processor (task or ISR) allowed to touch the critical
* Acquiring processor means the current processor (task or ISR) allowed to touch the critical
* resources, or the SPI bus.
*
* States of the lock:
@ -168,7 +168,7 @@ typedef struct spi_bus_lock_t spi_bus_lock_t;
* This flag is weak, will not prevent acquiring of devices. But will help the BG to be re-enabled again after the bus is release.
*/
// get the bit mask wher bit [high-1, low] are all 1'b1 s.
// get the bit mask where bit [high-1, low] are all 1'b1 s.
#define BIT1_MASK(high, low) ((UINT32_MAX << (high)) ^ (UINT32_MAX << (low)))
#define LOCK_BIT(mask) ((mask) << LOCK_SHIFT)
@ -238,7 +238,7 @@ struct spi_bus_lock_dev_t {
* acquire_end_core():
* uint32_t status = lock_status_clear(lock, dev_handle->mask & LOCK_MASK);
*
* Becuase this is the first `spi_hdl_1`, so after this , lock_bits == 0`b0. status == 0
* Because this is the first `spi_hdl_1`, so after this , lock_bits == 0`b0. status == 0
*
* 2. spi_hdl_2:
* acquire_core:
@ -254,7 +254,7 @@ struct spi_bus_lock_dev_t {
*
* 5. spi_hdl_1:
* acquire_end_core:
* status is 0, so it cleas the lock->acquiring_dev
* status is 0, so it clears the lock->acquiring_dev
*
* 6. spi_hdl_2:
* spi_device_polling_end:
@ -482,7 +482,7 @@ SPI_BUS_LOCK_ISR_ATTR static inline void update_pend_core(spi_bus_lock_t *lock,
}
// Clear the PEND bit (not REQ bit!) of a device, return the suggestion whether we can try to quit the ISR.
// Lost the acquiring processor immediately when the BG bits for active device are inactive, indiciating by the return value.
// Lost the acquiring processor immediately when the BG bits for active device are inactive, indicating by the return value.
// Can be called only when ISR is acting as the acquiring processor.
SPI_BUS_LOCK_ISR_ATTR static inline bool clear_pend_core(spi_bus_lock_dev_t *dev_handle)
{
@ -585,7 +585,7 @@ SPI_BUS_LOCK_ISR_ATTR static inline esp_err_t dev_wait(spi_bus_lock_dev_t *dev_h
******************************************************************************/
esp_err_t spi_bus_init_lock(spi_bus_lock_handle_t *out_lock, const spi_bus_lock_config_t *config)
{
spi_bus_lock_t* lock = (spi_bus_lock_t*)calloc(sizeof(spi_bus_lock_t), 1);
spi_bus_lock_t* lock = (spi_bus_lock_t*)calloc(1, sizeof(spi_bus_lock_t));
if (lock == NULL) {
return ESP_ERR_NO_MEM;
}
@ -644,7 +644,7 @@ esp_err_t spi_bus_lock_register_dev(spi_bus_lock_handle_t lock, spi_bus_lock_dev
return ESP_ERR_NOT_SUPPORTED;
}
spi_bus_lock_dev_t* dev_lock = (spi_bus_lock_dev_t*)heap_caps_calloc(sizeof(spi_bus_lock_dev_t), 1, MALLOC_CAP_INTERNAL | MALLOC_CAP_8BIT);
spi_bus_lock_dev_t* dev_lock = (spi_bus_lock_dev_t*)heap_caps_calloc(1, sizeof(spi_bus_lock_dev_t), MALLOC_CAP_INTERNAL | MALLOC_CAP_8BIT);
if (dev_lock == NULL) {
return ESP_ERR_NO_MEM;
}

View File

@ -132,7 +132,7 @@ static esp_err_t load_partitions(void)
#endif
// allocate new linked list item and populate it with data from partition table
partition_list_item_t *item = (partition_list_item_t *) calloc(sizeof(partition_list_item_t), 1);
partition_list_item_t *item = (partition_list_item_t *) calloc(1, sizeof(partition_list_item_t));
if (item == NULL) {
err = ESP_ERR_NO_MEM;
break;
@ -406,7 +406,7 @@ esp_err_t esp_partition_register_external(esp_flash_t *flash_chip, size_t offset
return err;
}
partition_list_item_t *item = (partition_list_item_t *) calloc(sizeof(partition_list_item_t), 1);
partition_list_item_t *item = (partition_list_item_t *) calloc(1, sizeof(partition_list_item_t));
if (item == NULL) {
return ESP_ERR_NO_MEM;
}

View File

@ -820,7 +820,7 @@ void esp_phy_load_cal_and_init(void)
#endif
esp_phy_calibration_data_t* cal_data =
(esp_phy_calibration_data_t*) calloc(sizeof(esp_phy_calibration_data_t), 1);
(esp_phy_calibration_data_t*) calloc(1, sizeof(esp_phy_calibration_data_t));
if (cal_data == NULL) {
ESP_LOGE(TAG, "failed to allocate memory for RF calibration data");
abort();

View File

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2018-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2018-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -28,7 +28,7 @@ on B. Note that this goes for every 32-byte cache line: this implies that if a p
A, the write to Y may show up before the write to X does.
It gets even worse when both A and B are written: theoretically, a write to a 32-byte cache line in A can be entirely
undone because of a write to a different addres in B that happens to be in the same 32-byte cache line.
undone because of a write to a different address in B that happens to be in the same 32-byte cache line.
Because of these reasons, we do not allow double mappings at all. This, however, has other implications that make
supporting ranges not really useful. Because the lack of double mappings, applications will need to do their own
@ -134,11 +134,9 @@ size_t esp_himem_reserved_area_size(void)
return CACHE_BLOCKSIZE * SPIRAM_BANKSWITCH_RESERVE;
}
#if SPIRAM_BANKSWITCH_RESERVE > 0
void __attribute__((constructor)) esp_himem_init(void)
{
if (SPIRAM_BANKSWITCH_RESERVE == 0) {
return;
}
uint32_t maxram = 0;
esp_psram_impl_get_available_size(&maxram);
//catch double init
@ -153,8 +151,8 @@ void __attribute__((constructor)) esp_himem_init(void)
int paddr_end = maxram;
s_ramblockcnt = ((paddr_end - paddr_start) / CACHE_BLOCKSIZE);
//Allocate data structures
s_ram_descriptor = calloc(sizeof(ramblock_t), s_ramblockcnt);
s_range_descriptor = calloc(sizeof(rangeblock_t), SPIRAM_BANKSWITCH_RESERVE);
s_ram_descriptor = calloc(s_ramblockcnt, sizeof(ramblock_t));
s_range_descriptor = calloc(SPIRAM_BANKSWITCH_RESERVE, sizeof(rangeblock_t));
if (s_ram_descriptor == NULL || s_range_descriptor == NULL) {
ESP_EARLY_LOGE(TAG, "Cannot allocate memory for meta info. Not initializing!");
free(s_ram_descriptor);
@ -164,6 +162,7 @@ void __attribute__((constructor)) esp_himem_init(void)
ESP_EARLY_LOGI(TAG, "Initialized. Using last %d 32KB address blocks for bank switching on %d KB of physical memory.",
SPIRAM_BANKSWITCH_RESERVE, (paddr_end - paddr_start) / 1024);
}
#endif
//Allocate count not-necessarily consecutive physical RAM blocks, return numbers in blocks[]. Return
//true if blocks can be allocated, false if not.
@ -195,11 +194,11 @@ esp_err_t esp_himem_alloc(size_t size, esp_himem_handle_t *handle_out)
return ESP_ERR_INVALID_SIZE;
}
int blocks = size / CACHE_BLOCKSIZE;
esp_himem_ramdata_t *r = calloc(sizeof(esp_himem_ramdata_t), 1);
esp_himem_ramdata_t *r = calloc(1, sizeof(esp_himem_ramdata_t));
if (!r) {
goto nomem;
}
r->block = calloc(sizeof(uint16_t), blocks);
r->block = calloc(blocks, sizeof(uint16_t));
if (!r->block) {
goto nomem;
}
@ -245,7 +244,7 @@ esp_err_t esp_himem_alloc_map_range(size_t size, esp_himem_rangehandle_t *handle
ESP_RETURN_ON_FALSE(s_ram_descriptor != NULL, ESP_ERR_INVALID_STATE, TAG, "Himem not available!");
ESP_RETURN_ON_FALSE(size % CACHE_BLOCKSIZE == 0, ESP_ERR_INVALID_SIZE, TAG, "requested size not aligned to blocksize");
int blocks = size / CACHE_BLOCKSIZE;
esp_himem_rangedata_t *r = calloc(sizeof(esp_himem_rangedata_t), 1);
esp_himem_rangedata_t *r = calloc(1, sizeof(esp_himem_rangedata_t));
if (!r) {
return ESP_ERR_NO_MEM;
}
@ -338,7 +337,7 @@ esp_err_t esp_himem_map(esp_himem_handle_t handle, esp_himem_rangehandle_t range
esp_err_t esp_himem_unmap(esp_himem_rangehandle_t range, void *ptr, size_t len)
{
//Note: doesn't actually unmap, just clears cache and marks blocks as unmapped.
//Future optimization: could actually lazy-unmap here: essentially, do nothing and only clear the cache when we re-use
//Future optimization: could actually lazy-unmap here: essentially, do nothing and only clear the cache when we reuse
//the block for a different physical address.
int range_offset = (uint32_t)ptr - VIRT_HIMEM_RANGE_START;
int range_block = (range_offset / CACHE_BLOCKSIZE) - range->block_start;

View File

@ -6,6 +6,7 @@
#include <stdlib.h>
#include <string.h>
#include "esp_macros.h"
#include "esp_err.h"
#include "esp_attr.h"
#include "esp_compiler.h"
@ -442,7 +443,7 @@ void esp_panic_handler(panic_info_t *info)
disable_all_wdts();
panic_print_str("CPU halted.\r\n");
esp_system_reset_modules_on_exit();
while (1);
ESP_INFINITE_LOOP();
#endif /* CONFIG_ESP_SYSTEM_PANIC_PRINT_REBOOT || CONFIG_ESP_SYSTEM_PANIC_SILENT_REBOOT */
#endif /* CONFIG_ESP_SYSTEM_PANIC_GDBSTUB */
}
@ -467,7 +468,7 @@ void IRAM_ATTR __attribute__((noreturn, no_sanitize_undefined)) panic_abort(cons
asm("unimp"); // should be an invalid operation on RISC-V targets
#endif
while (1);
ESP_INFINITE_LOOP();
}
/* Weak versions of reset reason hint functions.

View File

@ -65,7 +65,7 @@ esp_err_t IRAM_ATTR esp_backtrace_print_from_frame(int depth, const esp_backtrac
}
//Initialize stk_frame with first frame of stack
esp_backtrace_frame_t stk_frame = { 0 };
esp_backtrace_frame_t stk_frame;
memcpy(&stk_frame, frame, sizeof(esp_backtrace_frame_t));
print_str("\r\n\r\nBacktrace:", panic);
@ -197,7 +197,7 @@ esp_err_t IRAM_ATTR esp_backtrace_print_all_tasks(int depth)
for (UBaseType_t task_idx = 0; task_idx < num_snapshots; task_idx++) {
bool cur_running = false;
TaskHandle_t task_hdl = (TaskHandle_t) task_snapshots[task_idx].pxTCB;
esp_backtrace_frame_t stk_frame;
esp_backtrace_frame_t stk_frame = {0};
// Check if the task is one of the currently running tasks
for (BaseType_t core_id = 0; core_id < configNUMBER_OF_CORES; core_id++) {

View File

@ -11,6 +11,7 @@
#include "esp_private/system_internal.h"
#include "esp_private/rtc_ctrl.h"
#include "esp_private/spi_flash_os.h"
#include "esp_macros.h"
#include "esp_log.h"
#include "esp_cpu.h"
#include "soc/soc.h"
@ -67,9 +68,8 @@ IRAM_ATTR static void rtc_brownout_isr_handler(void *arg)
}
esp_rom_software_reset_system();
while (true) {
;
}
ESP_INFINITE_LOOP();
}
#endif // CONFIG_ESP_SYSTEM_BROWNOUT_INTR

View File

@ -5,6 +5,7 @@
*/
#include <stdint.h>
#include "esp_macros.h"
#include "esp_cpu.h"
#include "soc/soc.h"
#include "soc/soc_caps.h"
@ -61,9 +62,8 @@ void IRAM_ATTR esp_restart_noos_dig(void)
#endif
// generate core reset
esp_rom_software_reset_system();
while (true) {
;
}
ESP_INFINITE_LOOP();
}
#endif

View File

@ -6,6 +6,8 @@
#include <stdlib.h>
#include "esp_macros.h"
#include "esp_ipc_isr.h"
#include "esp_private/system_internal.h"
#include "esp_private/cache_utils.h"
@ -124,7 +126,7 @@ static void frame_to_panic_info(void *frame, panic_info_t *info, bool pseudo_exc
FORCE_INLINE_ATTR __attribute__((__noreturn__))
void busy_wait(void)
{
while (1) {;} // infinite loop
ESP_INFINITE_LOOP();
}
#endif // !CONFIG_ESP_SYSTEM_SINGLE_CORE_MODE

View File

@ -1,10 +1,11 @@
/*
* SPDX-FileCopyrightText: 2018-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2018-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <string.h>
#include "esp_macros.h"
#include "esp_system.h"
#include "esp_private/system_internal.h"
#include "esp_attr.h"
@ -140,7 +141,6 @@ void IRAM_ATTR esp_restart_noos(void)
esp_cpu_unstall(0);
esp_rom_software_reset_cpu(1);
}
while (true) {
;
}
ESP_INFINITE_LOOP();
}

View File

@ -1,11 +1,12 @@
/*
* SPDX-FileCopyrightText: 2018-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2018-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <string.h>
#include "sdkconfig.h"
#include "esp_macros.h"
#include "esp_system.h"
#include "esp_private/system_internal.h"
#include "esp_attr.h"
@ -95,7 +96,5 @@ void IRAM_ATTR esp_restart_noos(void)
// Reset CPU
esp_rom_software_reset_cpu(0);
while (true) {
;
}
ESP_INFINITE_LOOP();
}

View File

@ -1,11 +1,12 @@
/*
* SPDX-FileCopyrightText: 2018-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2018-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <string.h>
#include "sdkconfig.h"
#include "esp_macros.h"
#include "esp_system.h"
#include "esp_private/system_internal.h"
#include "esp_attr.h"
@ -107,7 +108,6 @@ void IRAM_ATTR esp_restart_noos(void)
// Reset CPU
esp_rom_software_reset_cpu(0);
while (true) {
;
}
ESP_INFINITE_LOOP();
}

View File

@ -6,6 +6,7 @@
#include <string.h>
#include "sdkconfig.h"
#include "esp_macros.h"
#include "esp_system.h"
#include "esp_private/system_internal.h"
#include "esp_attr.h"
@ -113,7 +114,6 @@ void IRAM_ATTR esp_restart_noos(void)
// Reset PRO CPU
esp_rom_software_reset_cpu(0);
while (true) {
;
}
ESP_INFINITE_LOOP();
}

View File

@ -1,11 +1,12 @@
/*
* SPDX-FileCopyrightText: 2022-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2022-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <string.h>
#include "sdkconfig.h"
#include "esp_macros.h"
#include "esp_system.h"
#include "esp_private/system_internal.h"
#include "esp_attr.h"
@ -112,7 +113,6 @@ void IRAM_ATTR esp_restart_noos(void)
// Reset PRO CPU
esp_rom_software_reset_cpu(0);
while (true) {
;
}
ESP_INFINITE_LOOP();
}

View File

@ -1,11 +1,12 @@
/*
* SPDX-FileCopyrightText: 2022-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2022-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <string.h>
#include "sdkconfig.h"
#include "esp_macros.h"
#include "esp_system.h"
#include "esp_private/system_internal.h"
#include "esp_attr.h"
@ -114,7 +115,5 @@ void IRAM_ATTR esp_restart_noos(void)
// Reset CPU
esp_rom_software_reset_cpu(0);
while (true) {
;
}
ESP_INFINITE_LOOP();
}

View File

@ -6,6 +6,7 @@
#include <string.h>
#include "sdkconfig.h"
#include "esp_macros.h"
#include "esp_system.h"
#include "esp_private/system_internal.h"
#include "esp_attr.h"
@ -164,7 +165,5 @@ void IRAM_ATTR esp_restart_noos(void)
}
#endif
while (true) {
;
}
ESP_INFINITE_LOOP();
}

View File

@ -1,11 +1,12 @@
/*
* SPDX-FileCopyrightText: 2018-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2018-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <string.h>
#include "sdkconfig.h"
#include "esp_macros.h"
#include "esp_system.h"
#include "esp_private/system_internal.h"
#include "esp_attr.h"
@ -114,7 +115,6 @@ void IRAM_ATTR esp_restart_noos(void)
// Reset CPUs
esp_rom_software_reset_cpu(0);
while (true) {
;
}
ESP_INFINITE_LOOP();
}

View File

@ -1,11 +1,12 @@
/*
* SPDX-FileCopyrightText: 2018-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2018-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <string.h>
#include "esp_macros.h"
#include "sdkconfig.h"
#include "esp_system.h"
#include "esp_private/system_internal.h"
@ -155,7 +156,6 @@ void IRAM_ATTR esp_restart_noos(void)
esp_rom_software_reset_cpu(1);
}
#endif
while (true) {
;
}
ESP_INFINITE_LOOP();
}

View File

@ -10,6 +10,7 @@
#include "esp_attr.h"
#include "esp_err.h"
#include "esp_compiler.h"
#include "esp_macros.h"
#include "esp_system.h"
#include "esp_log.h"
@ -213,5 +214,6 @@ static void start_cpu0_default(void)
#endif
esp_startup_start_app();
while (1);
ESP_INFINITE_LOOP();
}

View File

@ -389,7 +389,7 @@ TEST_CASE("esp_timer for very short intervals", "[esp_timer]")
}
#if !CONFIG_IDF_TARGET_ESP32C61 // TODO: IDF-10955, test fail
TEST_CASE("esp_timer_get_time call takes less than 1us", "[esp_timer]")
static void IRAM_ATTR test_esp_timer_get_time_performance(void)
{
int64_t begin = esp_timer_get_time();
volatile int64_t end;
@ -400,6 +400,11 @@ TEST_CASE("esp_timer_get_time call takes less than 1us", "[esp_timer]")
int ns_per_call = (int)((end - begin) * 1000 / iter_count);
TEST_PERFORMANCE_LESS_THAN(ESP_TIMER_GET_TIME_PER_CALL, "%dns", ns_per_call);
}
TEST_CASE("esp_timer_get_time call takes less than 1us", "[esp_timer]")
{
test_esp_timer_get_time_performance();
}
#endif
static int64_t IRAM_ATTR __attribute__((noinline)) get_clock_diff(void)

View File

@ -292,7 +292,7 @@ esp_err_t esp_vfs_fat_sdmmc_mount(const char* base_path,
s_saved_ctx_id = 0;
}
ctx = calloc(sizeof(vfs_fat_sd_ctx_t), 1);
ctx = calloc(1, sizeof(vfs_fat_sd_ctx_t));
if (!ctx) {
CHECK_EXECUTE_RESULT(ESP_ERR_NO_MEM, "no mem");
}
@ -390,7 +390,7 @@ esp_err_t esp_vfs_fat_sdspi_mount(const char* base_path,
s_saved_ctx_id = 0;
}
ctx = calloc(sizeof(vfs_fat_sd_ctx_t), 1);
ctx = calloc(1, sizeof(vfs_fat_sd_ctx_t));
if (!ctx) {
CHECK_EXECUTE_RESULT(ESP_ERR_NO_MEM, "no mem");
}

View File

@ -163,7 +163,7 @@ esp_err_t esp_vfs_fat_spiflash_mount_rw_wl(const char* base_path,
goto fail;
}
ctx = calloc(sizeof(vfs_fat_spiflash_ctx_t), 1);
ctx = calloc(1, sizeof(vfs_fat_spiflash_ctx_t));
ESP_GOTO_ON_FALSE(ctx, ESP_ERR_NO_MEM, fail, TAG, "no mem");
ctx->partition = data_partition;
ctx->by_label = (partition_label != NULL);

View File

@ -249,7 +249,7 @@ else()
idf_component_optional_requires(PRIVATE esp_pm)
endif()
if(CONFIG_IDF_TARGET_ESP32P4 AND NOT CONFIG_FREERTOS_SMP AND
if(NOT CONFIG_FREERTOS_SMP AND
CONFIG_COMPILER_STATIC_ANALYZER AND CMAKE_C_COMPILER_ID STREQUAL "GNU") # suppress false-positive warning
set_source_files_properties(
"${kernel_impl}/queue.c"

View File

@ -7,6 +7,7 @@
#include <stddef.h>
#include <string.h>
#include "sdkconfig.h"
#include "esp_compiler.h"
#include "hal/twai_hal.h"
#ifdef CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT
@ -190,7 +191,12 @@ void twai_hal_set_tx_buffer_and_transmit(twai_hal_context_t *hal_ctx, twai_hal_f
}
TWAI_HAL_SET_BITS(hal_ctx->state_flags, TWAI_HAL_STATE_FLAG_TX_BUFF_OCCUPIED);
#if defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
if (&hal_ctx->tx_frame_save == tx_frame) {
return;
}
//Save transmitted frame in case we need to retry
ESP_COMPILER_DIAGNOSTIC_PUSH_IGNORE("-Wanalyzer-overlapping-buffers") // TODO IDF-11085
memcpy(&hal_ctx->tx_frame_save, tx_frame, sizeof(twai_hal_frame_t));
ESP_COMPILER_DIAGNOSTIC_POP("-Wanalyzer-overlapping-buffers")
#endif //defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
}

View File

@ -34,6 +34,8 @@ int scandir(const char *dirname, struct dirent ***out_dirlist,
dir_ptr = opendir(dirname);
ESP_GOTO_ON_FALSE(dir_ptr, -1, out, TAG, "Failed to open directory: %s", dirname);
ESP_COMPILER_DIAGNOSTIC_PUSH_IGNORE("-Wanalyzer-malloc-leak") // Ignore intended return of allocated *out_dirlist
while ((entry = readdir(dir_ptr)) != NULL) {
/* skip entries that don't match the filter function */
if (select_func != NULL && !select_func(entry)) {
@ -72,7 +74,6 @@ out:
free(entries);
}
ESP_COMPILER_DIAGNOSTIC_PUSH_IGNORE("-Wanalyzer-malloc-leak") // Ignore intended return of allocated *out_dirlist
if (dir_ptr) {
closedir(dir_ptr);
}

View File

@ -163,6 +163,7 @@ esp_err_t esp_pthread_set_cfg(const esp_pthread_cfg_t *cfg)
/* If a value is already set, update that value */
esp_pthread_cfg_t *p = pthread_getspecific(s_pthread_cfg_key);
ESP_COMPILER_DIAGNOSTIC_PUSH_IGNORE("-Wanalyzer-malloc-leak") // ignore leak of 'p'
if (!p) {
p = malloc(sizeof(esp_pthread_cfg_t));
if (!p) {
@ -173,7 +174,6 @@ esp_err_t esp_pthread_set_cfg(const esp_pthread_cfg_t *cfg)
p->stack_alloc_caps = heap_caps;
pthread_setspecific(s_pthread_cfg_key, p);
ESP_COMPILER_DIAGNOSTIC_PUSH_IGNORE("-Wanalyzer-malloc-leak") // ignore leak of 'p'
return 0;
ESP_COMPILER_DIAGNOSTIC_POP("-Wanalyzer-malloc-leak")
}

View File

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2015-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2015-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -204,7 +204,7 @@ static esp_err_t esp_spiffs_init(const esp_vfs_spiffs_conf_t* conf)
return ESP_ERR_INVALID_ARG;
}
esp_spiffs_t * efs = calloc(sizeof(esp_spiffs_t), 1);
esp_spiffs_t * efs = calloc(1, sizeof(esp_spiffs_t));
if (efs == NULL) {
ESP_LOGE(TAG, "esp_spiffs could not be malloced");
return ESP_ERR_NO_MEM;
@ -229,7 +229,7 @@ static esp_err_t esp_spiffs_init(const esp_vfs_spiffs_conf_t* conf)
}
efs->fds_sz = conf->max_files * sizeof(spiffs_fd);
efs->fds = calloc(efs->fds_sz, 1);
efs->fds = calloc(1, efs->fds_sz);
if (efs->fds == NULL) {
ESP_LOGE(TAG, "fd buffer could not be allocated");
esp_spiffs_free(&efs);
@ -239,7 +239,7 @@ static esp_err_t esp_spiffs_init(const esp_vfs_spiffs_conf_t* conf)
#if SPIFFS_CACHE
efs->cache_sz = sizeof(spiffs_cache) + conf->max_files * (sizeof(spiffs_cache_page)
+ efs->cfg.log_page_size);
efs->cache = calloc(efs->cache_sz, 1);
efs->cache = calloc(1, efs->cache_sz);
if (efs->cache == NULL) {
ESP_LOGE(TAG, "cache buffer could not be allocated");
esp_spiffs_free(&efs);
@ -248,14 +248,14 @@ static esp_err_t esp_spiffs_init(const esp_vfs_spiffs_conf_t* conf)
#endif
const uint32_t work_sz = efs->cfg.log_page_size * 2;
efs->work = calloc(work_sz, 1);
efs->work = calloc(1, work_sz);
if (efs->work == NULL) {
ESP_LOGE(TAG, "work buffer could not be allocated");
esp_spiffs_free(&efs);
return ESP_ERR_NO_MEM;
}
efs->fs = calloc(sizeof(spiffs), 1);
efs->fs = calloc(1, sizeof(spiffs));
if (efs->fs == NULL) {
ESP_LOGE(TAG, "spiffs could not be allocated");
esp_spiffs_free(&efs);

View File

@ -0,0 +1,30 @@
GCC
***
:link_to_translation:`zh_CN:[中文]`
GCC Version
===========
The previous GCC version was GCC 13.2.0. This has now been upgraded to GCC 14.2.0 on all targets. Users that need to port their code from GCC 13.2.0 to 14.2.0 should refer to the series of official GCC porting guides listed below:
* `Porting to GCC 14 <https://gcc.gnu.org/gcc-14/porting_to.html>`_
Warnings
========
The upgrade to GCC 14.2.0 has resulted in the addition of new warnings, or enhancements to existing warnings. The full details of all GCC warnings can be found in `GCC Warning Options <https://gcc.gnu.org/onlinedocs/gcc-14.2.0/gcc/Warning-Options.html>`_. Users are advised to double-check their code, then fix the warnings if possible. Unfortunately, depending on the warning and the complexity of the user's code, some warnings will be false positives that require non-trivial fixes. In such cases, users can choose to suppress the warning in multiple ways. This section outlines some common warnings that users are likely to encounter and ways to fix them.
To suprress all new warnings enable ``CONFIG_COMPILER_DISABLE_GCC14_WARNINGS`` config option.
``-Wno-calloc-transposed-args``
-------------------------------
This is a coding style warning. The first argument to calloc() is documented to be number of elements in array, while the second argument is size of each element.
.. code-block:: c
calloc (sizeof (int), n); // warning
calloc (n, sizeof (int)); // ok

View File

@ -6,5 +6,6 @@ Migration from 5.3 to 5.4
.. toctree::
:maxdepth: 1
gcc
system
bluetooth-classic

View File

@ -0,0 +1,30 @@
GCC
***
:link_to_translation:`en:[English]`
GCC 版本
========
ESP-IDF 之前使用的 GCC 版本为 13.2.0,现已针对所有芯片目标升级至 GCC 14.2.0。若需要将代码从 GCC 13.2.0 迁移到 GCC 14.2.0,请参考以下 GCC 官方迁移指南。
* `迁移至 GCC 14 <https://gcc.gnu.org/gcc-14/porting_to.html>`_
警告
====
升级至 GCC 14.2.0 后会触发新警告,或是导致原有警告内容发生变化。了解所有 GCC 警告的详细内容,请参考 `GCC 警告选项 <https://gcc.gnu.org/onlinedocs/gcc-14.2.0/gcc/Warning-Options.html>`_。建议用户仔细检查代码,并尽量解决这些警告。但由于某些警告的特殊性及用户代码的复杂性,有些警告可能为误报,需要进行关键修复。在这种情况下,用户可以采取多种方式来抑制警告。本节介绍了用户可能遇到的常见警告及如何修复这些警告。
要抑制所有新的警告,请启用 CONFIG_COMPILER_DISABLE_GCC14_WARNINGS 配置选项。
``-Wno-calloc-transposed-args``
-------------------------------
这是一个编码风格警告。根据文档说明calloc() 的第一个参数应为数组元素的数量,第二个参数为每个元素的大小。
.. code-block:: c
calloc (sizeof (int), n); // 警告
calloc (n, sizeof (int)); // 好的

View File

@ -6,5 +6,6 @@
.. toctree::
:maxdepth: 1
gcc
system
bluetooth-classic

View File

@ -1,5 +1,5 @@
dependencies:
espressif/esp_cam_sensor: "^0.2.2"
espressif/esp_cam_sensor: "^0.5.1"
espressif/esp_lcd_ili9881c: "~0.2.0"
idf:
version: ">=5.3.0"

View File

@ -25,7 +25,7 @@ esp_err_t i2c_eeprom_init(i2c_master_bus_handle_t bus_handle, const i2c_eeprom_c
{
esp_err_t ret = ESP_OK;
i2c_eeprom_handle_t out_handle;
out_handle = (i2c_eeprom_handle_t)calloc(1, sizeof(i2c_eeprom_handle_t));
out_handle = (i2c_eeprom_handle_t)calloc(1, sizeof(*out_handle));
ESP_GOTO_ON_FALSE(out_handle, ESP_ERR_NO_MEM, err, TAG, "no memory for i2c eeprom device");
i2c_device_config_t i2c_dev_conf = {

View File

@ -98,7 +98,7 @@ class PublicHeaderChecker:
self.static_assert = re.compile(r'(_Static_assert|static_assert)')
self.defines_assert = re.compile(r'#define[ \t]+ESP_STATIC_ASSERT')
self.auto_soc_header = re.compile(r'components/soc/esp[a-z0-9_]+(?:/\w+)?/include/(soc|modem)/[a-zA-Z0-9_]+.h')
self.assembly_nocode = r'^\s*(\.file|\.text|\.ident|\.option|\.attribute).*$'
self.assembly_nocode = r'^\s*(\.file|\.text|\.ident|\.option|\.attribute|(\.section)?).*$'
self.check_threads: List[Thread] = []
self.stdc = '--std=c99'
self.stdcpp = '--std=c++17'
@ -259,7 +259,7 @@ class PublicHeaderChecker:
pass
# Get compilation data from an example to list all public header files
def list_public_headers(self, ignore_dirs: List, ignore_files: Union[List, Set], only_dir: str=None) -> None:
def list_public_headers(self, ignore_dirs: List, ignore_files: Union[List, Set], only_dir: Optional[str]=None) -> None:
idf_path = os.getenv('IDF_PATH')
if idf_path is None:
raise RuntimeError("Environment variable 'IDF_PATH' wasn't set.")

View File

@ -4,7 +4,7 @@
* SPDX-License-Identifier: Unlicense OR CC0-1.0
*/
/*
* Current (2023-05-04) value for -std=gnu++23 and -std=gnu++2b.
* Current GCC-14.2.0 value for -std=gnu++23 and -std=gnu++2b.
* If you change the C++ standard for IDF, you also need to change this.
*/
static_assert(__cplusplus == 202100L);
static_assert(__cplusplus == 202302L);

View File

@ -312,8 +312,8 @@ void test_coredump_summary(void)
void test_tcb_corrupted(void)
{
uint32_t *tcb_ptr = (uint32_t *)xTaskGetIdleTaskHandleForCore(0);
for (size_t i = 0; i < sizeof(StaticTask_t) / sizeof(uint32_t); ++i) {
uint32_t volatile *tcb_ptr = (uint32_t *)xTaskGetIdleTaskHandleForCore(0);
for (size_t i = 0; i < sizeof(StaticTask_t) / sizeof(uint32_t); i++) {
tcb_ptr[i] = 0xDEADBEE0;
}
vTaskDelay(2);

View File

@ -180,51 +180,51 @@
"versions": [
{
"linux-amd64": {
"sha256": "fcef03d87eac44c0dbee2bbee98443ed2fcf82720dcd8ebfe00640807b0f07c2",
"size": 112073272,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/xtensa-esp-elf-13.2.0_20240530-x86_64-linux-gnu.tar.xz"
"sha256": "e7c01501d5e32d317c3fadb9d97d1988b586c6e051c6d75a3bbcef3357ce1a51",
"size": 169472448,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-14.2.0_20240906/xtensa-esp-elf-14.2.0_20240906-x86_64-linux-gnu.tar.xz"
},
"linux-arm64": {
"sha256": "cfe55b92b4baeaa4309a948ba65e2adfc2d17a542c64856e36650869b419574a",
"size": 102954792,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/xtensa-esp-elf-13.2.0_20240530-aarch64-linux-gnu.tar.xz"
"sha256": "13d593a288a94c7e29b5ac4cf872608dfb4c61a0378265f355134fc5e69d38cc",
"size": 176939860,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-14.2.0_20240906/xtensa-esp-elf-14.2.0_20240906-aarch64-linux-gnu.tar.xz"
},
"linux-armel": {
"sha256": "c57a062969ec3d98b02a97cd9240eb31091957788509b60c356b0a6f23032669",
"size": 104791600,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/xtensa-esp-elf-13.2.0_20240530-arm-linux-gnueabi.tar.xz"
"sha256": "917c8339811ff1c7cb8911fa7d79618bebe58ece58da514f1b42d30c78f87b66",
"size": 174825600,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-14.2.0_20240906/xtensa-esp-elf-14.2.0_20240906-arm-linux-gnueabi.tar.xz"
},
"linux-armhf": {
"sha256": "1adc660f4d7bcf863f54051c5843719456fabc7203c1d4ccbb855924fda82987",
"size": 101896352,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/xtensa-esp-elf-13.2.0_20240530-arm-linux-gnueabihf.tar.xz"
"sha256": "5034c79a8bcf7acac1a44dec7cf6ff379b96a11dd597c09089b5f7acbd7a3d40",
"size": 168455332,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-14.2.0_20240906/xtensa-esp-elf-14.2.0_20240906-arm-linux-gnueabihf.tar.xz"
},
"linux-i686": {
"sha256": "f9203673aa0c42b041847c86b07e6f5b4aa9c90e6ff03d3cd3146928784447ea",
"size": 112724172,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/xtensa-esp-elf-13.2.0_20240530-i586-linux-gnu.tar.xz"
"sha256": "36c7234ab2712d34df8d36ad7b119ff6c6807068f7d2d9c8b2b3261f1dd54aa1",
"size": 179380376,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-14.2.0_20240906/xtensa-esp-elf-14.2.0_20240906-i586-linux-gnu.tar.xz"
},
"macos": {
"sha256": "39ee7df749f4ceb93624d73627688d5b86269a7429022f986f2940499936aacd",
"size": 114904912,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/xtensa-esp-elf-13.2.0_20240530-x86_64-apple-darwin.tar.xz"
"sha256": "499dc8492046c878b5173fcefafb90fad06e4294613e0b934ca57767e552e285",
"size": 182793460,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-14.2.0_20240906/xtensa-esp-elf-14.2.0_20240906-x86_64-apple-darwin.tar.xz"
},
"macos-arm64": {
"sha256": "d967e49a64f823e18fbae273efb1b094ac55e2207aa21fd3947c9d59f999f47e",
"size": 100018744,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/xtensa-esp-elf-13.2.0_20240530-aarch64-apple-darwin.tar.xz"
"sha256": "0450fc0c91688960a41b3a213e5b6ed387bc81af53d7428f074fb0a560b53070",
"size": 167977516,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-14.2.0_20240906/xtensa-esp-elf-14.2.0_20240906-aarch64-apple-darwin.tar.xz"
},
"name": "esp-13.2.0_20240530",
"name": "esp-14.2.0_20240906",
"status": "recommended",
"win32": {
"sha256": "d6b227c50e3c8e21d62502b3140e5ab74a4cb502c2b4169c36238b9858a8fb88",
"size": 266042967,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/xtensa-esp-elf-13.2.0_20240530-i686-w64-mingw32_hotfix.zip"
"sha256": "231de9e8a02df3bcc4be5d1db925f255ff30155706a48f8f1581f9b017a91e31",
"size": 382459137,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-14.2.0_20240906/xtensa-esp-elf-14.2.0_20240906-i686-w64-mingw32.zip"
},
"win64": {
"sha256": "155ee97b531236e6a7c763395c68ca793e55e74d2cb4d38a23057a153e01e7d0",
"size": 269831985,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/xtensa-esp-elf-13.2.0_20240530-x86_64-w64-mingw32_hotfix.zip"
"sha256": "5691206046de955bd503f320afadc40105bdb457bb7898ca1230365ac7084a00",
"size": 386315382,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-14.2.0_20240906/xtensa-esp-elf-14.2.0_20240906-x86_64-w64-mingw32.zip"
}
}
]
@ -327,51 +327,51 @@
"versions": [
{
"linux-amd64": {
"sha256": "f69a491d2f42f63e119f9077da995f7743ea8e1bf6944166a42a312cf60728a8",
"size": 145544808,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/riscv32-esp-elf-13.2.0_20240530-x86_64-linux-gnu.tar.xz"
"sha256": "c20b1ee91611622364146be5709decb03451af3f39fd1bce0636fc49d6391e3d",
"size": 298115680,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-14.2.0_20240906/riscv32-esp-elf-14.2.0_20240906-x86_64-linux-gnu.tar.xz"
},
"linux-arm64": {
"sha256": "276351b883a53e81b695d858be74114a8b627bbe4fc9c69ef46a7127ab143680",
"size": 145564848,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/riscv32-esp-elf-13.2.0_20240530-aarch64-linux-gnu.tar.xz"
"sha256": "dfb8e029c09a5a5dba16fa8d9e5a5008a80b9c843467d863102ec5359f9b77d2",
"size": 290828164,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-14.2.0_20240906/riscv32-esp-elf-14.2.0_20240906-aarch64-linux-gnu.tar.xz"
},
"linux-armel": {
"sha256": "14890f2a624e70f11da7268347adf25b6c396f42bcd4d8ac3c5bfa4050b7c934",
"size": 140376832,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/riscv32-esp-elf-13.2.0_20240530-arm-linux-gnueabi.tar.xz"
"sha256": "9079fdcf3b4126b5420a0bf0f5b5bfd164353127c8992a82fdf71e63bbe3295d",
"size": 288740796,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-14.2.0_20240906/riscv32-esp-elf-14.2.0_20240906-arm-linux-gnueabi.tar.xz"
},
"linux-armhf": {
"sha256": "b61ca9ceff25986ec1d166a01319bff09639be1d4ee5bf117502ce564fdae7e9",
"size": 142416372,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/riscv32-esp-elf-13.2.0_20240530-arm-linux-gnueabihf.tar.xz"
"sha256": "a09bfd82f321176621499632b0956b988dc8a93de74f2f99c7ae33a07c44762e",
"size": 294845076,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-14.2.0_20240906/riscv32-esp-elf-14.2.0_20240906-arm-linux-gnueabihf.tar.xz"
},
"linux-i686": {
"sha256": "12ef50f96deb9040ce360974a4237c64ae0706b0c429b90cecc8ab664cf6dbb4",
"size": 156221552,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/riscv32-esp-elf-13.2.0_20240530-i586-linux-gnu.tar.xz"
"sha256": "1a178e5ac934260cbecbaa3bc6caf838662dc4f3947ed23da5a5fc7f7dc52e7a",
"size": 300184408,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-14.2.0_20240906/riscv32-esp-elf-14.2.0_20240906-i586-linux-gnu.tar.xz"
},
"macos": {
"sha256": "cfbf5deaba05bf217701c8ceab7396bb0c2ca95ab58e134d4b2e175b86c2fd6c",
"size": 152568972,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/riscv32-esp-elf-13.2.0_20240530-x86_64-apple-darwin.tar.xz"
"sha256": "40bc1e783e1119aceb59b3f7a1cec633d91f7a89a39ec04d6a3408b31eff17d4",
"size": 305185164,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-14.2.0_20240906/riscv32-esp-elf-14.2.0_20240906-x86_64-apple-darwin.tar.xz"
},
"macos-arm64": {
"sha256": "230628fcf464ca8856c82c55514e40a8919e97fbc5e66b7165ca42c9653d2302",
"size": 136326672,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/riscv32-esp-elf-13.2.0_20240530-aarch64-apple-darwin.tar.xz"
"sha256": "cce902f01cb261905f5898d30887b81704a2b9d0f5de0d3806be7bfad55a505d",
"size": 285201616,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-14.2.0_20240906/riscv32-esp-elf-14.2.0_20240906-aarch64-apple-darwin.tar.xz"
},
"name": "esp-13.2.0_20240530",
"name": "esp-14.2.0_20240906",
"status": "recommended",
"win32": {
"sha256": "590bfb10576702639825581cc00c445da6e577012840a787137417e80d15f46d",
"size": 366573064,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/riscv32-esp-elf-13.2.0_20240530-i686-w64-mingw32.zip"
"sha256": "bdd12a07934e68ec7abafa4142399d87f62f06c37c451d0ddaba6299be2b51a7",
"size": 672058026,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-14.2.0_20240906/riscv32-esp-elf-14.2.0_20240906-i686-w64-mingw32.zip"
},
"win64": {
"sha256": "413eb9f6adf8fdaf25544d014c850fc09eb38bb93a2fc5ebd107ab1b0de1bb3a",
"size": 369820297,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/riscv32-esp-elf-13.2.0_20240530-x86_64-w64-mingw32.zip"
"sha256": "3631a8a8a72b9860fd823674918d118c696f920849c783f673b86adceeeeea7a",
"size": 677815737,
"url": "https://github.com/espressif/crosstool-NG/releases/download/esp-14.2.0_20240906/riscv32-esp-elf-14.2.0_20240906-x86_64-w64-mingw32.zip"
}
}
]