soc: espressif: move code start prior hw init
Make sure vector table and BSS clean up is performed pior hardware initialization. Signed-off-by: Sylvio Alves <sylvio.alves@espressif.com>
This commit is contained in:
parent
7b8a5ed655
commit
e36d702acd
28 changed files with 273 additions and 540 deletions
|
@ -19,6 +19,7 @@
|
|||
#include <soc/spi_struct.h>
|
||||
#include <esp_flash_encrypt.h>
|
||||
#include <esp_flash_internal.h>
|
||||
#include <bootloader_flash_priv.h>
|
||||
|
||||
#include <zephyr/kernel.h>
|
||||
#include <zephyr/device.h>
|
||||
|
@ -69,21 +70,49 @@ static inline void flash_esp32_sem_give(const struct device *dev)
|
|||
|
||||
#endif /* CONFIG_MULTITHREADING */
|
||||
|
||||
#include <zephyr/kernel.h>
|
||||
#include <zephyr/logging/log.h>
|
||||
#include <zephyr/sys/util.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
static int flash_esp32_read(const struct device *dev, off_t address, void *buffer, size_t length)
|
||||
{
|
||||
int ret = 0;
|
||||
|
||||
flash_esp32_sem_take(dev);
|
||||
#ifdef CONFIG_MCUBOOT
|
||||
/* ensure everything is 4-byte aligned */
|
||||
size_t aligned_length = ROUND_UP(length, 4);
|
||||
off_t aligned_address = ROUND_DOWN(address, 4);
|
||||
size_t address_offset = address - aligned_address;
|
||||
uint32_t temp_buf[aligned_length / 4];
|
||||
|
||||
if (!esp_flash_encryption_enabled()) {
|
||||
ret = esp_flash_read(NULL, buffer, address, length);
|
||||
ret = esp_rom_flash_read(aligned_address, temp_buf, aligned_length, false);
|
||||
} else {
|
||||
ret = esp_flash_read_encrypted(NULL, address, buffer, length);
|
||||
ret = esp_rom_flash_read(aligned_address, temp_buf, aligned_length, true);
|
||||
}
|
||||
|
||||
memcpy((void *)buffer, ((uint8_t *)temp_buf) + address_offset, length);
|
||||
#else
|
||||
|
||||
flash_esp32_sem_take(dev);
|
||||
|
||||
if (esp_flash_encryption_enabled()) {
|
||||
ret = esp_flash_read_encrypted(NULL, address, buffer, length);
|
||||
} else {
|
||||
ret = esp_flash_read(NULL, buffer, address, length);
|
||||
}
|
||||
|
||||
flash_esp32_sem_give(dev);
|
||||
|
||||
#endif
|
||||
|
||||
if (ret != 0) {
|
||||
LOG_ERR("esp_flash_read failed %d", ret);
|
||||
LOG_ERR("Flash read error: %d", ret);
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -94,28 +123,55 @@ static int flash_esp32_write(const struct device *dev,
|
|||
{
|
||||
int ret = 0;
|
||||
|
||||
flash_esp32_sem_take(dev);
|
||||
#ifdef CONFIG_MCUBOOT
|
||||
/* ensure everything is 4-byte aligned */
|
||||
size_t aligned_length = ROUND_UP(length, 4);
|
||||
off_t aligned_address = ROUND_DOWN(address, 4);
|
||||
size_t address_offset = address - aligned_address;
|
||||
uint32_t temp_buf[aligned_length / 4];
|
||||
|
||||
if (!esp_flash_encryption_enabled()) {
|
||||
ret = esp_flash_write(NULL, buffer, address, length);
|
||||
ret = esp_rom_flash_write(aligned_address, temp_buf, aligned_length, false);
|
||||
} else {
|
||||
ret = esp_flash_write_encrypted(NULL, address, buffer, length);
|
||||
ret = esp_rom_flash_write(aligned_address, temp_buf, aligned_length, true);
|
||||
}
|
||||
|
||||
memcpy((void *)buffer, ((uint8_t *)temp_buf) + address_offset, length);
|
||||
#else
|
||||
|
||||
flash_esp32_sem_take(dev);
|
||||
|
||||
if (esp_flash_encryption_enabled()) {
|
||||
ret = esp_flash_write_encrypted(NULL, address, buffer, length);
|
||||
} else {
|
||||
ret = esp_flash_write(NULL, buffer, address, length);
|
||||
}
|
||||
|
||||
flash_esp32_sem_give(dev);
|
||||
|
||||
#endif
|
||||
|
||||
if (ret != 0) {
|
||||
LOG_ERR("esp_flash_write failed %d", ret);
|
||||
LOG_ERR("Flash write error: %d", ret);
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int flash_esp32_erase(const struct device *dev, off_t start, size_t len)
|
||||
{
|
||||
int ret = 0;
|
||||
|
||||
#ifdef CONFIG_MCUBOOT
|
||||
ret = esp_rom_flash_erase_range(start, len);
|
||||
#else
|
||||
flash_esp32_sem_take(dev);
|
||||
int ret = esp_flash_erase_region(NULL, start, len);
|
||||
ret = esp_flash_erase_region(NULL, start, len);
|
||||
flash_esp32_sem_give(dev);
|
||||
#endif
|
||||
if (ret != 0) {
|
||||
LOG_ERR("esp_flash_erase_region failed %d", ret);
|
||||
LOG_ERR("Flash erase error: %d", ret);
|
||||
return -EIO;
|
||||
}
|
||||
return 0;
|
||||
|
@ -146,18 +202,12 @@ flash_esp32_get_parameters(const struct device *dev)
|
|||
|
||||
static int flash_esp32_init(const struct device *dev)
|
||||
{
|
||||
uint32_t ret = 0;
|
||||
|
||||
#ifdef CONFIG_MULTITHREADING
|
||||
struct flash_esp32_dev_data *const dev_data = dev->data;
|
||||
|
||||
k_sem_init(&dev_data->sem, 1, 1);
|
||||
#endif /* CONFIG_MULTITHREADING */
|
||||
ret = esp_flash_init_default_chip();
|
||||
if (ret != 0) {
|
||||
LOG_ERR("esp_flash_init_default_chip failed %d", ret);
|
||||
return 0;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
|
|
@ -21,9 +21,11 @@
|
|||
#include <esp_log.h>
|
||||
#include <bootloader_clock.h>
|
||||
#include <bootloader_common.h>
|
||||
|
||||
#include <esp_cpu.h>
|
||||
|
||||
#include <zephyr/linker/linker-defs.h>
|
||||
#include <kernel_internal.h>
|
||||
|
||||
#if CONFIG_SOC_SERIES_ESP32C6
|
||||
#include <soc/hp_apm_reg.h>
|
||||
#include <soc/lp_apm_reg.h>
|
||||
|
@ -99,13 +101,6 @@ static struct rom_segments map = {
|
|||
.drom_size = (uint32_t)&_image_drom_size,
|
||||
};
|
||||
|
||||
#ifndef CONFIG_BOOTLOADER_MCUBOOT
|
||||
static int spi_flash_read(uint32_t address, void *buffer, size_t length)
|
||||
{
|
||||
return esp_flash_read(NULL, buffer, address, length);
|
||||
}
|
||||
#endif /* CONFIG_BOOTLOADER_MCUBOOT */
|
||||
|
||||
void map_rom_segments(int core, struct rom_segments *map)
|
||||
{
|
||||
uint32_t app_irom_vaddr_align = map->irom_map_addr & MMU_FLASH_MASK;
|
||||
|
@ -126,7 +121,8 @@ void map_rom_segments(int core, struct rom_segments *map)
|
|||
|
||||
while (segments++ < 16) {
|
||||
|
||||
if (spi_flash_read(offset, &segment_hdr, sizeof(esp_image_segment_header_t)) != 0) {
|
||||
if (esp_rom_flash_read(offset, &segment_hdr,
|
||||
sizeof(esp_image_segment_header_t), true) != 0) {
|
||||
ESP_EARLY_LOGE(TAG, "Failed to read segment header at %x", offset);
|
||||
abort();
|
||||
}
|
||||
|
@ -255,6 +251,13 @@ void map_rom_segments(int core, struct rom_segments *map)
|
|||
void __start(void)
|
||||
{
|
||||
#ifdef CONFIG_RISCV_GP
|
||||
|
||||
__asm__ __volatile__("la t0, _esp_vector_table\n"
|
||||
"csrw mtvec, t0\n");
|
||||
|
||||
/* Disable normal interrupts. */
|
||||
csr_read_clear(mstatus, MSTATUS_MIE);
|
||||
|
||||
/* Configure the global pointer register
|
||||
* (This should be the first thing startup does, as any other piece of code could be
|
||||
* relaxed by the linker to access something relative to __global_pointer$)
|
||||
|
@ -263,17 +266,40 @@ void __start(void)
|
|||
".option norelax\n"
|
||||
"la gp, __global_pointer$\n"
|
||||
".option pop");
|
||||
#endif
|
||||
|
||||
#ifndef CONFIG_BOOTLOADER_MCUBOOT
|
||||
/* Init fundamental components */
|
||||
z_bss_zero();
|
||||
|
||||
#else /* xtensa */
|
||||
|
||||
extern uint32_t _init_start;
|
||||
|
||||
/* Move the exception vector table to IRAM. */
|
||||
__asm__ __volatile__("wsr %0, vecbase" : : "r"(&_init_start));
|
||||
|
||||
z_bss_zero();
|
||||
|
||||
__asm__ __volatile__("" : : "g"(&__bss_start) : "memory");
|
||||
|
||||
/* Disable normal interrupts. */
|
||||
__asm__ __volatile__("wsr %0, PS" : : "r"(PS_INTLEVEL(XCHAL_EXCM_LEVEL) | PS_UM | PS_WOE));
|
||||
|
||||
/* Initialize the architecture CPU pointer. Some of the
|
||||
* initialization code wants a valid arch_current_thread() before
|
||||
* arch_kernel_init() is invoked.
|
||||
*/
|
||||
__asm__ __volatile__("wsr.MISC0 %0; rsync" : : "r"(&_kernel.cpus[0]));
|
||||
|
||||
#endif /* CONFIG_RISCV_GP */
|
||||
|
||||
/* Initialize hardware only during 1st boot */
|
||||
#if defined(CONFIG_MCUBOOT) || defined(CONFIG_ESP_SIMPLE_BOOT)
|
||||
if (hardware_init()) {
|
||||
ESP_EARLY_LOGE(TAG, "HW init failed, aborting");
|
||||
abort();
|
||||
}
|
||||
#endif
|
||||
|
||||
#if !defined(CONFIG_MCUBOOT)
|
||||
#if defined(CONFIG_ESP_SIMPLE_BOOT) || defined(CONFIG_BOOTLOADER_MCUBOOT)
|
||||
map_rom_segments(0, &map);
|
||||
|
||||
/* Show map segments continue using same log format as during MCUboot phase */
|
||||
|
@ -282,19 +308,19 @@ void __start(void)
|
|||
ESP_EARLY_LOGI(TAG, "%s segment: paddr=%08xh, vaddr=%08xh, size=%05Xh (%6d) map", "DROM",
|
||||
map.drom_flash_offset, map.drom_map_addr, map.drom_size, map.drom_size);
|
||||
esp_rom_uart_tx_wait_idle(CONFIG_ESP_CONSOLE_UART_NUM);
|
||||
#endif
|
||||
|
||||
#ifndef CONFIG_SOC_SERIES_ESP32C2
|
||||
/* Disable RNG entropy source as it was already used */
|
||||
soc_random_disable();
|
||||
#endif
|
||||
#if defined(CONFIG_SOC_SERIES_ESP32S3) || defined(CONFIG_SOC_SERIES_ESP32C3)
|
||||
|
||||
/* Disable glitch detection as it can be falsely triggered by EMI interference */
|
||||
ESP_EARLY_LOGI(TAG, "Disabling glitch detection");
|
||||
ana_clock_glitch_reset_config(false);
|
||||
#endif
|
||||
#ifndef CONFIG_MCUBOOT
|
||||
|
||||
ESP_EARLY_LOGI(TAG, "libc heap size %d kB.", libc_heap_size / 1024);
|
||||
|
||||
__esp_platform_app_start();
|
||||
#endif /* CONFIG_ESP_SIMPLE_BOOT || CONFIG_BOOTLOADER_MCUBOOT */
|
||||
|
||||
#if defined(CONFIG_MCUBOOT)
|
||||
__esp_platform_mcuboot_start();
|
||||
#endif
|
||||
__esp_platform_start();
|
||||
}
|
||||
|
|
|
@ -453,4 +453,10 @@ int esp_appcpu_init(void)
|
|||
|
||||
return 0;
|
||||
}
|
||||
|
||||
#if !defined(CONFIG_MCUBOOT)
|
||||
extern int esp_appcpu_init(void);
|
||||
SYS_INIT(esp_appcpu_init, POST_KERNEL, CONFIG_KERNEL_INIT_PRIORITY_DEFAULT);
|
||||
#endif
|
||||
|
||||
#endif /* CONFIG_SOC_ENABLE_APPCPU */
|
||||
|
|
|
@ -57,14 +57,8 @@ int hardware_init(void)
|
|||
print_banner();
|
||||
#endif /* CONFIG_ESP_CONSOLE */
|
||||
|
||||
spi_flash_init_chip_state();
|
||||
err = esp_flash_init_default_chip();
|
||||
if (err != 0) {
|
||||
ESP_EARLY_LOGE(TAG, "Failed to init flash chip, error %d", err);
|
||||
return err;
|
||||
}
|
||||
|
||||
reset_mmu();
|
||||
|
||||
flash_update_id();
|
||||
|
||||
err = bootloader_flash_xmc_startup();
|
||||
|
@ -90,6 +84,7 @@ int hardware_init(void)
|
|||
|
||||
check_wdt_reset();
|
||||
config_wdt();
|
||||
|
||||
soc_random_enable();
|
||||
|
||||
return 0;
|
||||
|
|
|
@ -1,109 +1,36 @@
|
|||
/*
|
||||
* Copyright (c) 2017 Intel Corporation
|
||||
* Copyright (c) 2025 Espressif Systems (Shanghai) CO LTD.
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
/* Include esp-idf headers first to avoid redefining BIT() macro */
|
||||
#include <soc.h>
|
||||
#include <soc/rtc_cntl_reg.h>
|
||||
#include <soc/timer_group_reg.h>
|
||||
#include <zephyr/drivers/interrupt_controller/intc_esp32.h>
|
||||
#include <xtensa/config/core-isa.h>
|
||||
#include <xtensa/corebits.h>
|
||||
#include <esp_private/spi_flash_os.h>
|
||||
#include <esp_private/esp_mmu_map_private.h>
|
||||
#include <esp_flash_internal.h>
|
||||
#if CONFIG_ESP_SPIRAM
|
||||
#include "psram.h"
|
||||
#endif
|
||||
|
||||
#include <zephyr/kernel_structs.h>
|
||||
#include <string.h>
|
||||
#include <zephyr/toolchain.h>
|
||||
#include <zephyr/types.h>
|
||||
#include <zephyr/linker/linker-defs.h>
|
||||
#include <kernel_internal.h>
|
||||
|
||||
#include <soc_init.h>
|
||||
#include <flash_init.h>
|
||||
#include <esp_private/cache_utils.h>
|
||||
#include <esp_private/system_internal.h>
|
||||
#include <esp32/rom/cache.h>
|
||||
#include <esp_cpu.h>
|
||||
#include <hal/soc_hal.h>
|
||||
#include <hal/cpu_hal.h>
|
||||
#include <soc/gpio_periph.h>
|
||||
#include <esp_err.h>
|
||||
#include <esp_timer.h>
|
||||
#include <hal/wdt_hal.h>
|
||||
#include <esp_app_format.h>
|
||||
|
||||
#ifndef CONFIG_SOC_ENABLE_APPCPU
|
||||
#include "esp_clk_internal.h"
|
||||
#endif /* CONFIG_SOC_ENABLE_APPCPU */
|
||||
|
||||
#include <psram.h>
|
||||
#include <zephyr/drivers/interrupt_controller/intc_esp32.h>
|
||||
#include <zephyr/sys/printk.h>
|
||||
#include "esp_log.h"
|
||||
|
||||
#define TAG "boot.esp32"
|
||||
|
||||
extern void z_prep_c(void);
|
||||
extern void esp_reset_reason_init(void);
|
||||
extern int esp_appcpu_init(void);
|
||||
|
||||
/*
|
||||
* This is written in C rather than assembly since, during the port bring up,
|
||||
* Zephyr is being booted by the Espressif bootloader. With it, the C stack
|
||||
* is already set up.
|
||||
*/
|
||||
void IRAM_ATTR __esp_platform_start(void)
|
||||
void IRAM_ATTR __esp_platform_app_start(void)
|
||||
{
|
||||
extern uint32_t _init_start;
|
||||
|
||||
/* Move the exception vector table to IRAM. */
|
||||
__asm__ __volatile__ ("wsr %0, vecbase" : : "r"(&_init_start));
|
||||
|
||||
z_bss_zero();
|
||||
|
||||
__asm__ __volatile__ ("" : : "g"(&__bss_start) : "memory");
|
||||
|
||||
/* Disable normal interrupts. */
|
||||
__asm__ __volatile__ ("wsr %0, PS" : : "r"(PS_INTLEVEL(XCHAL_EXCM_LEVEL) | PS_UM | PS_WOE));
|
||||
|
||||
/* Initialize the architecture CPU pointer. Some of the
|
||||
* initialization code wants a valid _current before
|
||||
* z_prep_c() is invoked.
|
||||
*/
|
||||
__asm__ __volatile__("wsr.MISC0 %0; rsync" : : "r"(&_kernel.cpus[0]));
|
||||
|
||||
esp_reset_reason_init();
|
||||
|
||||
#ifndef CONFIG_MCUBOOT
|
||||
/* ESP-IDF/MCUboot 2nd stage bootloader enables RTC WDT to check
|
||||
* on startup sequence related issues in application. Hence disable that
|
||||
* as we are about to start Zephyr environment.
|
||||
*/
|
||||
wdt_hal_context_t rtc_wdt_ctx = {.inst = WDT_RWDT, .rwdt_dev = &RTCCNTL};
|
||||
|
||||
wdt_hal_write_protect_disable(&rtc_wdt_ctx);
|
||||
wdt_hal_disable(&rtc_wdt_ctx);
|
||||
wdt_hal_write_protect_enable(&rtc_wdt_ctx);
|
||||
|
||||
esp_timer_early_init();
|
||||
|
||||
esp_mspi_pin_init();
|
||||
|
||||
esp_flash_app_init();
|
||||
|
||||
esp_mmu_map_init();
|
||||
|
||||
#if CONFIG_ESP_SPIRAM
|
||||
esp_init_psram();
|
||||
#endif /* CONFIG_ESP_SPIRAM */
|
||||
|
||||
#endif /* !CONFIG_MCUBOOT */
|
||||
esp_flash_config();
|
||||
|
||||
esp_intr_initialize();
|
||||
|
||||
#if CONFIG_ESP_SPIRAM
|
||||
esp_init_psram();
|
||||
|
||||
/* Init Shared Multi Heap for PSRAM */
|
||||
int err = esp_psram_smh_init();
|
||||
|
||||
|
@ -118,6 +45,16 @@ void IRAM_ATTR __esp_platform_start(void)
|
|||
CODE_UNREACHABLE;
|
||||
}
|
||||
|
||||
void IRAM_ATTR __esp_platform_mcuboot_start(void)
|
||||
{
|
||||
esp_intr_initialize();
|
||||
|
||||
/* Start Zephyr */
|
||||
z_prep_c();
|
||||
|
||||
CODE_UNREACHABLE;
|
||||
}
|
||||
|
||||
/* Boot-time static default printk handler, possibly to be overridden later. */
|
||||
int IRAM_ATTR arch_printk_char_out(int c)
|
||||
{
|
||||
|
@ -132,8 +69,3 @@ void sys_arch_reboot(int type)
|
|||
{
|
||||
esp_restart_noos();
|
||||
}
|
||||
|
||||
#if defined(CONFIG_SOC_ENABLE_APPCPU) && !defined(CONFIG_MCUBOOT)
|
||||
extern int esp_appcpu_init(void);
|
||||
SYS_INIT(esp_appcpu_init, POST_KERNEL, CONFIG_KERNEL_INIT_PRIORITY_DEFAULT);
|
||||
#endif
|
||||
|
|
|
@ -20,7 +20,8 @@
|
|||
#include <xtensa/core-macros.h>
|
||||
#include <esp_private/esp_clk.h>
|
||||
|
||||
void __esp_platform_start(void);
|
||||
void __esp_platform_mcuboot_start(void);
|
||||
void __esp_platform_app_start(void);
|
||||
|
||||
static inline void esp32_set_mask32(uint32_t v, uint32_t mem_addr)
|
||||
{
|
||||
|
|
|
@ -212,6 +212,7 @@ SECTIONS
|
|||
*libzephyr.a:console_init.*(.literal .text .literal.* .text.*)
|
||||
*libzephyr.a:soc_init.*(.literal .text .literal.* .text.*)
|
||||
*libzephyr.a:hw_init.*(.literal .text .literal.* .text.*)
|
||||
*libzephyr.a:soc_random.*(.literal .text .literal.* .text.*)
|
||||
*libarch__riscv__core.a:(.literal .text .literal.* .text.*)
|
||||
*libsubsys__net__l2__ethernet.a:(.literal .text .literal.* .text.*)
|
||||
*libsubsys__net__lib__config.a:(.literal .text .literal.* .text.*)
|
||||
|
@ -357,7 +358,6 @@ SECTIONS
|
|||
|
||||
*libzephyr.a:esp_image_format.*(.literal .text .literal.* .text.*)
|
||||
*libzephyr.a:flash_ops.*(.literal .text .literal.* .text.*)
|
||||
*libzephyr.a:flash_ops_esp32c2.*(.literal .text .literal.* .text.*)
|
||||
*libzephyr.a:flash_encrypt.*(.literal .text .literal.* .text.*)
|
||||
*libzephyr.a:flash_encryption_secure_features.*(.literal .text .literal.* .text.*)
|
||||
*libzephyr.a:flash_partitions.*(.literal .text .literal.* .text.*)
|
||||
|
@ -463,6 +463,7 @@ SECTIONS
|
|||
*libzephyr.a:console_init.*(.rodata .rodata.*)
|
||||
*libzephyr.a:soc_init.*(.rodata .rodata.*)
|
||||
*libzephyr.a:hw_init.*(.rodata .rodata.*)
|
||||
*libzephyr.a:soc_random.*(.rodata .rodata.*)
|
||||
*libzephyr.a:cache_utils.*(.rodata .rodata.* .srodata .srodata.*)
|
||||
|
||||
/* [mapping:hal] */
|
||||
|
|
|
@ -57,15 +57,9 @@ int hardware_init(void)
|
|||
print_banner();
|
||||
#endif /* CONFIG_ESP_CONSOLE */
|
||||
|
||||
spi_flash_init_chip_state();
|
||||
err = esp_flash_init_default_chip();
|
||||
if (err != 0) {
|
||||
ESP_EARLY_LOGE(TAG, "Failed to init flash chip, error %d", err);
|
||||
return err;
|
||||
}
|
||||
|
||||
cache_hal_init();
|
||||
mmu_hal_init();
|
||||
|
||||
flash_update_id();
|
||||
|
||||
err = bootloader_flash_xmc_startup();
|
||||
|
@ -92,5 +86,7 @@ int hardware_init(void)
|
|||
check_wdt_reset();
|
||||
config_wdt();
|
||||
|
||||
soc_random_enable();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
|
|
@ -1,83 +1,39 @@
|
|||
/*
|
||||
* Copyright (c) 2024 Espressif Systems (Shanghai) Co., Ltd.
|
||||
* Copyright (c) 2024-2025 Espressif Systems (Shanghai) Co., Ltd.
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
/* Include esp-idf headers first to avoid redefining BIT() macro */
|
||||
#include <soc/rtc_cntl_reg.h>
|
||||
#include <soc/timer_group_reg.h>
|
||||
#include <soc/ext_mem_defs.h>
|
||||
#include <soc/gpio_reg.h>
|
||||
#include <soc/syscon_reg.h>
|
||||
#include <soc/system_reg.h>
|
||||
#include "hal/wdt_hal.h"
|
||||
#include "esp_cpu.h"
|
||||
#include "hal/soc_hal.h"
|
||||
#include "hal/cpu_hal.h"
|
||||
#include "esp_timer.h"
|
||||
#include "esp_private/system_internal.h"
|
||||
#include "esp_clk_internal.h"
|
||||
#include <soc/interrupt_reg.h>
|
||||
#include <esp_private/spi_flash_os.h>
|
||||
#include "esp_private/esp_mmu_map_private.h"
|
||||
#include <esp_flash_internal.h>
|
||||
|
||||
#include <soc.h>
|
||||
#include <soc_init.h>
|
||||
#include <flash_init.h>
|
||||
#include <esp_private/cache_utils.h>
|
||||
#include <esp_private/system_internal.h>
|
||||
#include <esp_timer.h>
|
||||
#include <zephyr/drivers/interrupt_controller/intc_esp32c3.h>
|
||||
|
||||
#include <zephyr/kernel_structs.h>
|
||||
#include <kernel_internal.h>
|
||||
#include <string.h>
|
||||
#include <zephyr/toolchain.h>
|
||||
#include <soc.h>
|
||||
|
||||
extern void esp_reset_reason_init(void);
|
||||
|
||||
/*
|
||||
* This is written in C rather than assembly since, during the port bring up,
|
||||
* Zephyr is being booted by the Espressif bootloader. With it, the C stack
|
||||
* is already set up.
|
||||
*/
|
||||
void __attribute__((section(".iram1"))) __esp_platform_start(void)
|
||||
void IRAM_ATTR __esp_platform_app_start(void)
|
||||
{
|
||||
__asm__ __volatile__("la t0, _esp32c2_vector_table\n"
|
||||
"csrw mtvec, t0\n");
|
||||
|
||||
z_bss_zero();
|
||||
|
||||
/* Disable normal interrupts. */
|
||||
csr_read_clear(mstatus, MSTATUS_MIE);
|
||||
|
||||
esp_reset_reason_init();
|
||||
|
||||
#ifndef CONFIG_MCUBOOT
|
||||
/* ESP-IDF 2nd stage bootloader enables RTC WDT to check on startup sequence
|
||||
* related issues in application. Hence disable that as we are about to start
|
||||
* Zephyr environment.
|
||||
*/
|
||||
wdt_hal_context_t rtc_wdt_ctx = {.inst = WDT_RWDT, .rwdt_dev = &RTCCNTL};
|
||||
|
||||
wdt_hal_write_protect_disable(&rtc_wdt_ctx);
|
||||
wdt_hal_disable(&rtc_wdt_ctx);
|
||||
wdt_hal_write_protect_enable(&rtc_wdt_ctx);
|
||||
|
||||
/* Enable wireless phy subsystem clock,
|
||||
* This needs to be done before the kernel starts
|
||||
*/
|
||||
REG_CLR_BIT(SYSTEM_WIFI_CLK_EN_REG, SYSTEM_WIFI_CLK_SDIOSLAVE_EN);
|
||||
SET_PERI_REG_MASK(SYSTEM_WIFI_CLK_EN_REG, SYSTEM_WIFI_CLK_EN);
|
||||
|
||||
esp_timer_early_init();
|
||||
|
||||
esp_mspi_pin_init();
|
||||
esp_flash_config();
|
||||
|
||||
esp_flash_app_init();
|
||||
esp_intr_initialize();
|
||||
|
||||
esp_mmu_map_init();
|
||||
/* Start Zephyr */
|
||||
z_cstart();
|
||||
|
||||
#endif /* !CONFIG_MCUBOOT */
|
||||
CODE_UNREACHABLE;
|
||||
}
|
||||
|
||||
/*Initialize the esp32c2 interrupt controller */
|
||||
void IRAM_ATTR __esp_platform_mcuboot_start(void)
|
||||
{
|
||||
esp_intr_initialize();
|
||||
|
||||
/* Start Zephyr */
|
||||
|
|
|
@ -18,7 +18,8 @@
|
|||
|
||||
#ifndef _ASMLANGUAGE
|
||||
|
||||
void __esp_platform_start(void);
|
||||
void __esp_platform_mcuboot_start(void);
|
||||
void __esp_platform_app_start(void);
|
||||
|
||||
static inline uint32_t esp_core_id(void)
|
||||
{
|
||||
|
|
|
@ -22,12 +22,12 @@ GTEXT(_isr_wrapper)
|
|||
* only uses the 24 MSBs of the MTVEC, i.e. (MTVEC & 0xffffff00).
|
||||
*/
|
||||
|
||||
.global _esp32c2_vector_table
|
||||
.global _esp_vector_table
|
||||
.section .exception_vectors.text
|
||||
.balign 0x100
|
||||
.type _esp32c2_vector_table, @function
|
||||
.type _esp_vector_table, @function
|
||||
|
||||
_esp32c2_vector_table:
|
||||
_esp_vector_table:
|
||||
.option push
|
||||
.option norvc
|
||||
.rept (32)
|
||||
|
|
|
@ -59,16 +59,9 @@ int hardware_init(void)
|
|||
print_banner();
|
||||
#endif /* CONFIG_ESP_CONSOLE */
|
||||
|
||||
|
||||
spi_flash_init_chip_state();
|
||||
err = esp_flash_init_default_chip();
|
||||
if (err != 0) {
|
||||
ESP_EARLY_LOGE(TAG, "Failed to init flash chip, error %d", err);
|
||||
return err;
|
||||
}
|
||||
|
||||
cache_hal_init();
|
||||
mmu_hal_init();
|
||||
|
||||
flash_update_id();
|
||||
|
||||
err = bootloader_flash_xmc_startup();
|
||||
|
|
|
@ -47,7 +47,7 @@
|
|||
#define BOOTLOADER_STACK_OVERHEAD 0x0
|
||||
/* These lengths can be adjusted, if necessary: */
|
||||
#define BOOTLOADER_DRAM_SEG_LEN 0x9800
|
||||
#define BOOTLOADER_IRAM_SEG_LEN 0x9800
|
||||
#define BOOTLOADER_IRAM_SEG_LEN 0x9C00
|
||||
#define BOOTLOADER_IRAM_LOADER_SEG_LEN 0x1400
|
||||
|
||||
/* Start of the lower region is determined by region size and the end of the higher region */
|
||||
|
|
|
@ -1,83 +1,40 @@
|
|||
/*
|
||||
* Copyright (c) 2021 Espressif Systems (Shanghai) Co., Ltd.
|
||||
* Copyright (c) 2025 Espressif Systems (Shanghai) CO LTD.
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
/* Include esp-idf headers first to avoid redefining BIT() macro */
|
||||
#include <soc/rtc_cntl_reg.h>
|
||||
#include <soc/timer_group_reg.h>
|
||||
#include <soc/ext_mem_defs.h>
|
||||
#include <soc/gpio_reg.h>
|
||||
#include <soc/syscon_reg.h>
|
||||
#include <soc/system_reg.h>
|
||||
#include "hal/wdt_hal.h"
|
||||
#include "esp_cpu.h"
|
||||
#include "hal/soc_hal.h"
|
||||
#include "hal/cpu_hal.h"
|
||||
#include "esp_timer.h"
|
||||
#include "esp_private/system_internal.h"
|
||||
#include "esp_clk_internal.h"
|
||||
#include <soc/interrupt_reg.h>
|
||||
#include <esp_private/spi_flash_os.h>
|
||||
#include "esp_private/esp_mmu_map_private.h"
|
||||
#include <esp_flash_internal.h>
|
||||
|
||||
#include <soc.h>
|
||||
#include <soc_init.h>
|
||||
#include <flash_init.h>
|
||||
#include <esp_private/cache_utils.h>
|
||||
#include <esp_private/system_internal.h>
|
||||
#include <esp_timer.h>
|
||||
#include <zephyr/drivers/interrupt_controller/intc_esp32c3.h>
|
||||
|
||||
#include <zephyr/kernel_structs.h>
|
||||
#include <kernel_internal.h>
|
||||
#include <string.h>
|
||||
#include <zephyr/toolchain.h>
|
||||
#include <soc.h>
|
||||
|
||||
extern void esp_reset_reason_init(void);
|
||||
|
||||
/*
|
||||
* This is written in C rather than assembly since, during the port bring up,
|
||||
* Zephyr is being booted by the Espressif bootloader. With it, the C stack
|
||||
* is already set up.
|
||||
*/
|
||||
void __attribute__((section(".iram1"))) __esp_platform_start(void)
|
||||
void IRAM_ATTR __esp_platform_app_start(void)
|
||||
{
|
||||
__asm__ __volatile__("la t0, _esp32c3_vector_table\n"
|
||||
"csrw mtvec, t0\n");
|
||||
|
||||
z_bss_zero();
|
||||
|
||||
/* Disable normal interrupts. */
|
||||
csr_read_clear(mstatus, MSTATUS_MIE);
|
||||
|
||||
esp_reset_reason_init();
|
||||
|
||||
#ifndef CONFIG_MCUBOOT
|
||||
/* ESP-IDF 2nd stage bootloader enables RTC WDT to check on startup sequence
|
||||
* related issues in application. Hence disable that as we are about to start
|
||||
* Zephyr environment.
|
||||
*/
|
||||
wdt_hal_context_t rtc_wdt_ctx = {.inst = WDT_RWDT, .rwdt_dev = &RTCCNTL};
|
||||
|
||||
wdt_hal_write_protect_disable(&rtc_wdt_ctx);
|
||||
wdt_hal_disable(&rtc_wdt_ctx);
|
||||
wdt_hal_write_protect_enable(&rtc_wdt_ctx);
|
||||
|
||||
/* Enable wireless phy subsystem clock,
|
||||
* This needs to be done before the kernel starts
|
||||
*/
|
||||
REG_CLR_BIT(SYSTEM_WIFI_CLK_EN_REG, SYSTEM_WIFI_CLK_SDIOSLAVE_EN);
|
||||
SET_PERI_REG_MASK(SYSTEM_WIFI_CLK_EN_REG, SYSTEM_WIFI_CLK_EN);
|
||||
|
||||
esp_timer_early_init();
|
||||
|
||||
esp_mspi_pin_init();
|
||||
esp_flash_config();
|
||||
|
||||
esp_flash_app_init();
|
||||
esp_intr_initialize();
|
||||
|
||||
esp_mmu_map_init();
|
||||
/* Start Zephyr */
|
||||
z_cstart();
|
||||
|
||||
#endif /* !CONFIG_MCUBOOT */
|
||||
CODE_UNREACHABLE;
|
||||
}
|
||||
|
||||
/*Initialize the esp32c3 interrupt controller */
|
||||
void IRAM_ATTR __esp_platform_mcuboot_start(void)
|
||||
{
|
||||
esp_intr_initialize();
|
||||
|
||||
/* Start Zephyr */
|
||||
|
|
|
@ -18,7 +18,8 @@
|
|||
|
||||
#ifndef _ASMLANGUAGE
|
||||
|
||||
void __esp_platform_start(void);
|
||||
void __esp_platform_mcuboot_start(void);
|
||||
void __esp_platform_app_start(void);
|
||||
|
||||
static inline uint32_t esp_core_id(void)
|
||||
{
|
||||
|
|
|
@ -22,12 +22,12 @@ GTEXT(_isr_wrapper)
|
|||
* only uses the 24 MSBs of the MTVEC, i.e. (MTVEC & 0xffffff00).
|
||||
*/
|
||||
|
||||
.global _esp32c3_vector_table
|
||||
.global _esp_vector_table
|
||||
.section .exception_vectors.text
|
||||
.balign 0x100
|
||||
.type _esp32c3_vector_table, @function
|
||||
.type _esp_vector_table, @function
|
||||
|
||||
_esp32c3_vector_table:
|
||||
_esp_vector_table:
|
||||
.option push
|
||||
.option norvc
|
||||
.rept (32)
|
||||
|
|
|
@ -75,13 +75,6 @@ int hardware_init(void)
|
|||
print_banner();
|
||||
#endif /* CONFIG_ESP_CONSOLE */
|
||||
|
||||
spi_flash_init_chip_state();
|
||||
err = esp_flash_init_default_chip();
|
||||
if (err != 0) {
|
||||
ESP_EARLY_LOGE(TAG, "Failed to init flash chip, error %d", err);
|
||||
return err;
|
||||
}
|
||||
|
||||
cache_hal_init();
|
||||
mmu_hal_init();
|
||||
|
||||
|
|
|
@ -1,73 +1,39 @@
|
|||
/*
|
||||
* Copyright (c) 2023 Espressif Systems (Shanghai) Co., Ltd.
|
||||
* Copyright (c) 2023-2025 Espressif Systems (Shanghai) Co., Ltd.
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
/* Include esp-idf headers first to avoid redefining BIT() macro */
|
||||
#include <soc/timer_group_reg.h>
|
||||
#include <soc/ext_mem_defs.h>
|
||||
#include <soc/gpio_reg.h>
|
||||
#include <soc/system_reg.h>
|
||||
#include "hal/wdt_hal.h"
|
||||
#include "esp_cpu.h"
|
||||
#include "hal/soc_hal.h"
|
||||
#include "hal/cpu_hal.h"
|
||||
#include "esp_timer.h"
|
||||
#include "esp_private/system_internal.h"
|
||||
#include "esp_clk_internal.h"
|
||||
#include <soc/interrupt_reg.h>
|
||||
#include <esp_private/spi_flash_os.h>
|
||||
#include "esp_private/esp_mmu_map_private.h"
|
||||
#include <esp_flash_internal.h>
|
||||
|
||||
#include <soc.h>
|
||||
#include <soc_init.h>
|
||||
#include <flash_init.h>
|
||||
#include <esp_private/cache_utils.h>
|
||||
#include <esp_private/system_internal.h>
|
||||
#include <esp_timer.h>
|
||||
#include <zephyr/drivers/interrupt_controller/intc_esp32c3.h>
|
||||
|
||||
#include <zephyr/kernel_structs.h>
|
||||
#include <kernel_internal.h>
|
||||
#include <string.h>
|
||||
#include <zephyr/toolchain/gcc.h>
|
||||
#include <soc.h>
|
||||
|
||||
/*
|
||||
* This is written in C rather than assembly since, during the port bring up,
|
||||
* Zephyr is being booted by the Espressif bootloader. With it, the C stack
|
||||
* is already set up.
|
||||
*/
|
||||
void IRAM_ATTR __esp_platform_start(void)
|
||||
extern void esp_reset_reason_init(void);
|
||||
|
||||
void IRAM_ATTR __esp_platform_app_start(void)
|
||||
{
|
||||
__asm__ __volatile__("la t0, _esp32c6_vector_table\n"
|
||||
"csrw mtvec, t0\n");
|
||||
|
||||
z_bss_zero();
|
||||
|
||||
/* Disable normal interrupts. */
|
||||
csr_read_clear(mstatus, MSTATUS_MIE);
|
||||
|
||||
esp_reset_reason_init();
|
||||
|
||||
#ifndef CONFIG_MCUBOOT
|
||||
/* ESP-IDF 2nd stage bootloader enables RTC WDT to check on startup sequence
|
||||
* related issues in application. Hence disable that as we are about to start
|
||||
* Zephyr environment.
|
||||
*/
|
||||
wdt_hal_context_t rtc_wdt_ctx = {.inst = WDT_RWDT, .rwdt_dev = &LP_WDT};
|
||||
|
||||
wdt_hal_write_protect_disable(&rtc_wdt_ctx);
|
||||
wdt_hal_disable(&rtc_wdt_ctx);
|
||||
wdt_hal_write_protect_enable(&rtc_wdt_ctx);
|
||||
|
||||
esp_timer_early_init();
|
||||
|
||||
esp_mspi_pin_init();
|
||||
esp_flash_config();
|
||||
|
||||
esp_flash_app_init();
|
||||
esp_intr_initialize();
|
||||
|
||||
esp_mmu_map_init();
|
||||
/* Start Zephyr */
|
||||
z_cstart();
|
||||
|
||||
#endif /* !CONFIG_MCUBOOT */
|
||||
CODE_UNREACHABLE;
|
||||
}
|
||||
|
||||
/*Initialize the esp32c6 interrupt controller */
|
||||
void IRAM_ATTR __esp_platform_mcuboot_start(void)
|
||||
{
|
||||
esp_intr_initialize();
|
||||
|
||||
/* Start Zephyr */
|
||||
|
|
|
@ -27,7 +27,8 @@
|
|||
|
||||
#ifndef _ASMLANGUAGE
|
||||
|
||||
void __esp_platform_start(void);
|
||||
void __esp_platform_mcuboot_start(void);
|
||||
void __esp_platform_app_start(void);
|
||||
|
||||
static inline uint32_t esp_core_id(void)
|
||||
{
|
||||
|
|
|
@ -22,12 +22,12 @@ GTEXT(_isr_wrapper)
|
|||
* only uses the 24 MSBs of the MTVEC, i.e. (MTVEC & 0xffffff00).
|
||||
*/
|
||||
|
||||
.global _esp32c6_vector_table
|
||||
.global _esp_vector_table
|
||||
.section .exception_vectors.text
|
||||
.balign 0x100
|
||||
.type _esp32c6_vector_table, @function
|
||||
.type _esp_vector_table, @function
|
||||
|
||||
_esp32c6_vector_table:
|
||||
_esp_vector_table:
|
||||
.option push
|
||||
.option norvc
|
||||
.rept (32)
|
||||
|
|
|
@ -57,14 +57,8 @@ int hardware_init(void)
|
|||
print_banner();
|
||||
#endif /* CONFIG_ESP_CONSOLE */
|
||||
|
||||
spi_flash_init_chip_state();
|
||||
err = esp_flash_init_default_chip();
|
||||
if (err != 0) {
|
||||
ESP_EARLY_LOGE(TAG, "Failed to init flash chip, error %d", err);
|
||||
return err;
|
||||
}
|
||||
|
||||
cache_hal_init();
|
||||
|
||||
mmu_hal_init();
|
||||
|
||||
/* Workaround: normal ROM bootloader exits with DROM0 cache unmasked, but 2nd bootloader
|
||||
|
|
|
@ -1,85 +1,24 @@
|
|||
/*
|
||||
* Copyright (c) 2021 Espressif Systems (Shanghai) Co., Ltd.
|
||||
* Copyright (c) 2021-2025 Espressif Systems (Shanghai) Co., Ltd.
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
/* Include esp-idf headers first to avoid redefining BIT() macro */
|
||||
#include "soc.h"
|
||||
#include <soc/rtc_cntl_reg.h>
|
||||
#include <soc/timer_group_reg.h>
|
||||
#include <zephyr/drivers/interrupt_controller/intc_esp32.h>
|
||||
#include <xtensa/config/core-isa.h>
|
||||
#include <xtensa/corebits.h>
|
||||
#include <esp_private/spi_flash_os.h>
|
||||
#include <esp_private/esp_mmu_map_private.h>
|
||||
#include <esp_flash_internal.h>
|
||||
#if CONFIG_ESP_SPIRAM
|
||||
#include "psram.h"
|
||||
#endif
|
||||
|
||||
#include <zephyr/kernel_structs.h>
|
||||
#include <kernel_internal.h>
|
||||
#include <string.h>
|
||||
#include <zephyr/toolchain.h>
|
||||
#include <zephyr/types.h>
|
||||
|
||||
#include <soc.h>
|
||||
#include <soc_init.h>
|
||||
#include <flash_init.h>
|
||||
#include <esp_private/cache_utils.h>
|
||||
#include <esp_private/system_internal.h>
|
||||
#include <esp32s2/rom/cache.h>
|
||||
#include <soc/gpio_periph.h>
|
||||
#include <esp_cpu.h>
|
||||
#include <hal/cpu_hal.h>
|
||||
#include <hal/soc_hal.h>
|
||||
#include <hal/wdt_hal.h>
|
||||
#include <esp_timer.h>
|
||||
#include <esp_err.h>
|
||||
#include <esp_clk_internal.h>
|
||||
#include <psram.h>
|
||||
#include <zephyr/drivers/interrupt_controller/intc_esp32.h>
|
||||
#include <zephyr/sys/printk.h>
|
||||
#include "esp_log.h"
|
||||
|
||||
#define TAG "boot.esp32s2"
|
||||
|
||||
extern void rtc_clk_cpu_freq_set_xtal(void);
|
||||
extern void esp_reset_reason_init(void);
|
||||
extern void z_prep_c(void);
|
||||
extern void esp_reset_reason_init(void);
|
||||
|
||||
/*
|
||||
* This is written in C rather than assembly since, during the port bring up,
|
||||
* Zephyr is being booted by the Espressif bootloader. With it, the C stack
|
||||
* is already set up.
|
||||
*/
|
||||
void __attribute__((section(".iram1"))) __esp_platform_start(void)
|
||||
void IRAM_ATTR __esp_platform_app_start(void)
|
||||
{
|
||||
extern uint32_t _init_start;
|
||||
|
||||
/* Move the exception vector table to IRAM. */
|
||||
__asm__ __volatile__("wsr %0, vecbase" : : "r"(&_init_start));
|
||||
|
||||
/* Zero out BSS */
|
||||
z_bss_zero();
|
||||
|
||||
/* Disable normal interrupts. */
|
||||
__asm__ __volatile__("wsr %0, PS" : : "r"(PS_INTLEVEL(XCHAL_EXCM_LEVEL) | PS_UM | PS_WOE));
|
||||
|
||||
/* Initialize the architecture CPU pointer. Some of the
|
||||
* initialization code wants a valid _current before
|
||||
* arch_kernel_init() is invoked.
|
||||
*/
|
||||
__asm__ __volatile__("wsr.MISC0 %0; rsync" : : "r"(&_kernel.cpus[0]));
|
||||
|
||||
esp_reset_reason_init();
|
||||
|
||||
#ifndef CONFIG_MCUBOOT
|
||||
/* ESP-IDF 2nd stage bootloader enables RTC WDT to check on startup sequence
|
||||
* related issues in application. Hence disable that as we are about to start
|
||||
* Zephyr environment.
|
||||
*/
|
||||
wdt_hal_context_t rtc_wdt_ctx = {.inst = WDT_RWDT, .rwdt_dev = &RTCCNTL};
|
||||
|
||||
wdt_hal_write_protect_disable(&rtc_wdt_ctx);
|
||||
wdt_hal_disable(&rtc_wdt_ctx);
|
||||
wdt_hal_write_protect_enable(&rtc_wdt_ctx);
|
||||
|
||||
/*
|
||||
* Configure the mode of instruction cache :
|
||||
* cache size, cache associated ways, cache line size.
|
||||
|
@ -96,23 +35,17 @@ void __attribute__((section(".iram1"))) __esp_platform_start(void)
|
|||
esp_config_data_cache_mode();
|
||||
esp_rom_Cache_Enable_DCache(0);
|
||||
|
||||
esp_reset_reason_init();
|
||||
|
||||
esp_timer_early_init();
|
||||
|
||||
esp_mspi_pin_init();
|
||||
|
||||
esp_flash_app_init();
|
||||
|
||||
esp_mmu_map_init();
|
||||
|
||||
#if CONFIG_ESP_SPIRAM
|
||||
esp_init_psram();
|
||||
#endif /* CONFIG_ESP_SPIRAM */
|
||||
|
||||
#endif /* !CONFIG_MCUBOOT */
|
||||
esp_flash_config();
|
||||
|
||||
esp_intr_initialize();
|
||||
|
||||
#if CONFIG_ESP_SPIRAM
|
||||
esp_init_psram();
|
||||
|
||||
/* Init Shared Multi Heap for PSRAM */
|
||||
int err = esp_psram_smh_init();
|
||||
|
||||
|
@ -127,6 +60,16 @@ void __attribute__((section(".iram1"))) __esp_platform_start(void)
|
|||
CODE_UNREACHABLE;
|
||||
}
|
||||
|
||||
void IRAM_ATTR __esp_platform_mcuboot_start(void)
|
||||
{
|
||||
esp_intr_initialize();
|
||||
|
||||
/* Start Zephyr */
|
||||
z_prep_c();
|
||||
|
||||
CODE_UNREACHABLE;
|
||||
}
|
||||
|
||||
/* Boot-time static default printk handler, possibly to be overridden later. */
|
||||
int IRAM_ATTR arch_printk_char_out(int c)
|
||||
{
|
||||
|
|
|
@ -22,7 +22,8 @@
|
|||
#include <zephyr/arch/xtensa/arch.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
void __esp_platform_start(void);
|
||||
void __esp_platform_mcuboot_start(void);
|
||||
void __esp_platform_app_start(void);
|
||||
|
||||
static inline uint32_t esp_core_id(void)
|
||||
{
|
||||
|
|
|
@ -191,4 +191,10 @@ int esp_appcpu_init(void)
|
|||
|
||||
return 0;
|
||||
}
|
||||
|
||||
#if !defined(CONFIG_MCUBOOT)
|
||||
extern int esp_appcpu_init(void);
|
||||
SYS_INIT(esp_appcpu_init, POST_KERNEL, CONFIG_KERNEL_INIT_PRIORITY_DEFAULT);
|
||||
#endif
|
||||
|
||||
#endif /* CONFIG_SOC_ENABLE_APPCPU */
|
||||
|
|
|
@ -63,14 +63,8 @@ int hardware_init(void)
|
|||
print_banner();
|
||||
#endif /* CONFIG_ESP_CONSOLE */
|
||||
|
||||
spi_flash_init_chip_state();
|
||||
err = esp_flash_init_default_chip();
|
||||
if (err != 0) {
|
||||
ESP_EARLY_LOGE(TAG, "Failed to init flash chip, error %d", err);
|
||||
return err;
|
||||
}
|
||||
|
||||
cache_hal_init();
|
||||
|
||||
mmu_hal_init();
|
||||
|
||||
flash_update_id();
|
||||
|
@ -97,6 +91,7 @@ int hardware_init(void)
|
|||
}
|
||||
|
||||
check_wdt_reset();
|
||||
|
||||
config_wdt();
|
||||
|
||||
soc_random_enable();
|
||||
|
|
|
@ -1,66 +1,23 @@
|
|||
/*
|
||||
* Copyright (c) 2017 Intel Corporation
|
||||
* Copyright (c) 2025 Espressif Systems (Shanghai) CO LTD.
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
/* Include esp-idf headers first to avoid redefining BIT() macro */
|
||||
#include <soc.h>
|
||||
#include <soc/rtc_cntl_reg.h>
|
||||
#include <soc/timer_group_reg.h>
|
||||
#include <soc/ext_mem_defs.h>
|
||||
#include <zephyr/drivers/interrupt_controller/intc_esp32.h>
|
||||
#include <xtensa/config/core-isa.h>
|
||||
#include <xtensa/corebits.h>
|
||||
#include <esp_private/spi_flash_os.h>
|
||||
#include <esp_private/esp_mmu_map_private.h>
|
||||
#include <esp_private/mspi_timing_tuning.h>
|
||||
#include <esp_flash_internal.h>
|
||||
#include <soc_init.h>
|
||||
#include <flash_init.h>
|
||||
#include <esp_private/cache_utils.h>
|
||||
#include <sdkconfig.h>
|
||||
|
||||
#if CONFIG_ESP_SPIRAM
|
||||
#include "psram.h"
|
||||
#endif
|
||||
|
||||
#include <zephyr/kernel_structs.h>
|
||||
#include <zephyr/toolchain.h>
|
||||
#include <zephyr/types.h>
|
||||
#include <zephyr/linker/linker-defs.h>
|
||||
#include <kernel_internal.h>
|
||||
#include <zephyr/sys/util.h>
|
||||
|
||||
#include <esp_private/system_internal.h>
|
||||
#include <esp32s3/rom/cache.h>
|
||||
#include <esp32s3/rom/rtc.h>
|
||||
#include <soc/syscon_reg.h>
|
||||
#include <hal/soc_hal.h>
|
||||
#include <hal/wdt_hal.h>
|
||||
#include <hal/cpu_hal.h>
|
||||
#include <esp_cpu.h>
|
||||
#include <soc/gpio_periph.h>
|
||||
#include <esp_err.h>
|
||||
#include <esp_timer.h>
|
||||
#include <esp_clk_internal.h>
|
||||
#include <esp_app_format.h>
|
||||
|
||||
#include <psram.h>
|
||||
#include <zephyr/drivers/interrupt_controller/intc_esp32.h>
|
||||
#include <zephyr/sys/printk.h>
|
||||
#include "esp_log.h"
|
||||
|
||||
#include <zephyr/drivers/flash.h>
|
||||
#include <zephyr/storage/flash_map.h>
|
||||
|
||||
#define TAG "boot.esp32s3"
|
||||
|
||||
extern void z_prep_c(void);
|
||||
extern void esp_reset_reason_init(void);
|
||||
extern int esp_appcpu_init(void);
|
||||
|
||||
#ifndef CONFIG_MCUBOOT
|
||||
/*
|
||||
* This function is a container for SoC patches
|
||||
* that needs to be applied during the startup.
|
||||
*/
|
||||
static void IRAM_ATTR esp_errata(void)
|
||||
{
|
||||
/* Handle the clock gating fix */
|
||||
|
@ -77,32 +34,9 @@ static void IRAM_ATTR esp_errata(void)
|
|||
Cache_Occupy_Addr(SOC_DROM_LOW, 0x4000);
|
||||
#endif
|
||||
}
|
||||
#endif /* CONFIG_MCUBOOT */
|
||||
|
||||
/*
|
||||
* This is written in C rather than assembly since, during the port bring up,
|
||||
* Zephyr is being booted by the Espressif bootloader. With it, the C stack
|
||||
* is already set up.
|
||||
*/
|
||||
void IRAM_ATTR __esp_platform_start(void)
|
||||
void IRAM_ATTR __esp_platform_app_start(void)
|
||||
{
|
||||
extern uint32_t _init_start;
|
||||
|
||||
/* Move the exception vector table to IRAM. */
|
||||
__asm__ __volatile__("wsr %0, vecbase" : : "r"(&_init_start));
|
||||
|
||||
z_bss_zero();
|
||||
|
||||
/* Disable normal interrupts. */
|
||||
__asm__ __volatile__("wsr %0, PS" : : "r"(PS_INTLEVEL(XCHAL_EXCM_LEVEL) | PS_UM | PS_WOE));
|
||||
|
||||
/* Initialize the architecture CPU pointer. Some of the
|
||||
* initialization code wants a valid _current before
|
||||
* arch_kernel_init() is invoked.
|
||||
*/
|
||||
__asm__ __volatile__("wsr.MISC0 %0; rsync" : : "r"(&_kernel.cpus[0]));
|
||||
|
||||
#ifndef CONFIG_MCUBOOT
|
||||
/* Configure the mode of instruction cache : cache size, cache line size. */
|
||||
esp_config_instruction_cache_mode();
|
||||
|
||||
|
@ -114,38 +48,17 @@ void IRAM_ATTR __esp_platform_start(void)
|
|||
/* Apply SoC patches */
|
||||
esp_errata();
|
||||
|
||||
/* ESP-IDF/MCUboot 2nd stage bootloader enables RTC WDT to check on startup sequence
|
||||
* related issues in application. Hence disable that as we are about to start
|
||||
* Zephyr environment.
|
||||
*/
|
||||
wdt_hal_context_t rtc_wdt_ctx = {.inst = WDT_RWDT, .rwdt_dev = &RTCCNTL};
|
||||
|
||||
wdt_hal_write_protect_disable(&rtc_wdt_ctx);
|
||||
wdt_hal_disable(&rtc_wdt_ctx);
|
||||
wdt_hal_write_protect_enable(&rtc_wdt_ctx);
|
||||
|
||||
esp_reset_reason_init();
|
||||
|
||||
esp_timer_early_init();
|
||||
|
||||
esp_mspi_pin_init();
|
||||
|
||||
esp_flash_app_init();
|
||||
|
||||
mspi_timing_flash_tuning();
|
||||
|
||||
esp_mmu_map_init();
|
||||
|
||||
#if CONFIG_ESP_SPIRAM
|
||||
esp_init_psram();
|
||||
#endif /* CONFIG_ESP_SPIRAM */
|
||||
|
||||
#endif /* !CONFIG_MCUBOOT */
|
||||
esp_flash_config();
|
||||
|
||||
esp_intr_initialize();
|
||||
|
||||
#if CONFIG_ESP_SPIRAM
|
||||
/* Init Shared Multi Heap for PSRAM */
|
||||
esp_init_psram();
|
||||
|
||||
int err = esp_psram_smh_init();
|
||||
|
||||
if (err) {
|
||||
|
@ -159,6 +72,16 @@ void IRAM_ATTR __esp_platform_start(void)
|
|||
CODE_UNREACHABLE;
|
||||
}
|
||||
|
||||
void IRAM_ATTR __esp_platform_mcuboot_start(void)
|
||||
{
|
||||
esp_intr_initialize();
|
||||
|
||||
/* Start Zephyr */
|
||||
z_prep_c();
|
||||
|
||||
CODE_UNREACHABLE;
|
||||
}
|
||||
|
||||
/* Boot-time static default printk handler, possibly to be overridden later. */
|
||||
int IRAM_ATTR arch_printk_char_out(int c)
|
||||
{
|
||||
|
@ -173,8 +96,3 @@ void sys_arch_reboot(int type)
|
|||
{
|
||||
esp_restart_noos();
|
||||
}
|
||||
|
||||
#if defined(CONFIG_SOC_ENABLE_APPCPU) && !defined(CONFIG_MCUBOOT)
|
||||
extern int esp_appcpu_init(void);
|
||||
SYS_INIT(esp_appcpu_init, POST_KERNEL, CONFIG_KERNEL_INIT_PRIORITY_DEFAULT);
|
||||
#endif
|
||||
|
|
|
@ -25,7 +25,8 @@
|
|||
#include <xtensa/core-macros.h>
|
||||
#include <esp_private/esp_clk.h>
|
||||
|
||||
void __esp_platform_start(void);
|
||||
void __esp_platform_mcuboot_start(void);
|
||||
void __esp_platform_app_start(void);
|
||||
|
||||
static inline void esp32_set_mask32(uint32_t v, uint32_t mem_addr)
|
||||
{
|
||||
|
|
2
west.yml
2
west.yml
|
@ -162,7 +162,7 @@ manifest:
|
|||
groups:
|
||||
- hal
|
||||
- name: hal_espressif
|
||||
revision: 970156407d42c968c50d4b2e3c85c0c548bd9a9e
|
||||
revision: a459b40356f5e6fb55d92bcb458cec45365d5ec5
|
||||
path: modules/hal/espressif
|
||||
west-commands: west/west-commands.yml
|
||||
groups:
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue