soc: esp32_net: added esp32_net as an option

to use esp32 core 1 as a separate CPU, also
provide infrastructure to load firmware to
that CPU

Signed-off-by: Felipe Neves <felipe.neves@linaro.org>
This commit is contained in:
Felipe Neves 2022-07-14 18:30:44 -03:00 committed by Carles Cufí
parent 0514c3b139
commit bb6e656ec0
23 changed files with 1518 additions and 18 deletions

View file

@ -0,0 +1,8 @@
# ESP32 board configuration
# Copyright (c) 2022 Espressif Systems (Shanghai) Co., Ltd.
# SPDX-License-Identifier: Apache-2.0
config BOARD_ESP32_NET
bool "ESP32 Board configuration for APP_CPU"
depends on SOC_ESP32_NET

View file

@ -0,0 +1,25 @@
# ESP32_NET board configuration
# Copyright (c) 2022 Espressif Systems (Shanghai) Co., Ltd.
# SPDX-License-Identifier: Apache-2.0
config BOARD
default "esp32_net"
depends on BOARD_ESP32_NET
config ENTROPY_ESP32_RNG
default y if ENTROPY_GENERATOR
if BT
config HEAP_MEM_POOL_SIZE
default 16384
config ENTROPY_GENERATOR
default y
choice BT_HCI_BUS_TYPE
default BT_ESP32
endchoice
endif # BT

View file

@ -0,0 +1,9 @@
# SPDX-License-Identifier: Apache-2.0
if(NOT "${OPENOCD}" MATCHES "^${ESPRESSIF_TOOLCHAIN_PATH}/.*")
set(OPENOCD OPENOCD-NOTFOUND)
endif()
find_program(OPENOCD openocd PATHS ${ESPRESSIF_TOOLCHAIN_PATH}/openocd-esp32/bin NO_DEFAULT_PATH)
include(${ZEPHYR_BASE}/boards/common/esp32.board.cmake)
include(${ZEPHYR_BASE}/boards/common/openocd.board.cmake)

View file

@ -0,0 +1,153 @@
.. _esp32_net:
ESP32-NET
#########
Overview
********
ESP32_NET is a board configuration to allow zephyr application building
targeted to ESP32 APP_CPU only, please refer ESP32 board to a more complete
list of features.
System requirements
*******************
Prerequisites
=============
The ESP32 toolchain :file:`xtensa-esp32-elf` is required to build this port.
The toolchain installation can be performed in two ways:
#. Automatic installation
.. code-block:: console
west espressif install
.. note::
By default, the toolchain will be downloaded and installed under $HOME/.espressif directory
(%USERPROFILE%/.espressif on Windows).
#. Manual installation
Follow the `ESP32 Toolchain`_ link to download proper OS package version.
Unpack the toolchain file to a known location as it will be required for environment path configuration.
Build Environment Setup
=======================
Some variables must be exported into the environment prior to building this port.
Find more information at :ref:`env_vars` on how to keep this settings saved in you environment.
.. note::
In case of manual toolchain installation, set :file:`ESPRESSIF_TOOLCHAIN_PATH` accordingly.
Otherwise, set toolchain path as below. If necessary, update the version folder path as in :file:`esp-2020r3-8.4.0`.
On Linux and macOS:
.. code-block:: console
export ZEPHYR_TOOLCHAIN_VARIANT="espressif"
export ESPRESSIF_TOOLCHAIN_PATH="${HOME}/.espressif/tools/zephyr"
On Windows:
.. code-block:: console
# on CMD:
set ESPRESSIF_TOOLCHAIN_PATH=%USERPROFILE%\.espressif\tools\zephyr
set ZEPHYR_TOOLCHAIN_VARIANT=espressif
# on PowerShell
$env:ESPRESSIF_TOOLCHAIN_PATH="$env:USERPROFILE\.espressif\tools\zephyr"
$env:ZEPHYR_TOOLCHAIN_VARIANT="espressif"
Finally, retrieve required submodules to build this port. This might take a while for the first time:
.. code-block:: console
west espressif update
.. note::
It is recommended running the command above after :file:`west update` so that submodules also get updated.
Flashing
========
The usual ``flash`` target will work with the ``esp32`` board
configuration. Here is an example for the :ref:`hello_world`
application.
.. zephyr-app-commands::
:zephyr-app: samples/hello_world
:board: esp32_net
:goals: flash
Refer to :ref:`build_an_application` and :ref:`application_run` for
more details.
It's impossible to determine which serial port the ESP32 board is
connected to, as it uses a generic RS232-USB converter. The default of
``/dev/ttyUSB0`` is provided as that's often the assigned name on a Linux
machine without any other such converters.
The baud rate of 921600bps is recommended. If experiencing issues when
flashing, try halving the value a few times (460800, 230400, 115200,
etc). It might be necessary to change the flash frequency or the flash
mode; please refer to the `esptool documentation`_ for guidance on these
settings.
All flashing options are now handled by the :ref:`west` tool, including flashing
with custom options such as a different serial port. The ``west`` tool supports
specific options for the ESP32 board, as listed here:
--esp-idf-path ESP_IDF_PATH
path to ESP-IDF
--esp-device ESP_DEVICE
serial port to flash, default $ESPTOOL_PORT if defined.
If not, esptool will loop over available serial ports until
it finds ESP32 device to flash.
--esp-baud-rate ESP_BAUD_RATE
serial baud rate, default 921600
--esp-flash-size ESP_FLASH_SIZE
flash size, default "detect"
--esp-flash-freq ESP_FLASH_FREQ
flash frequency, default "40m"
--esp-flash-mode ESP_FLASH_MODE
flash mode, default "dio"
--esp-tool ESP_TOOL if given, complete path to espidf. default is to
search for it in [ESP_IDF_PATH]/components/esptool_py/
esptool/esptool.py
--esp-flash-bootloader ESP_FLASH_BOOTLOADER
Bootloader image to flash
--esp-flash-partition_table ESP_FLASH_PARTITION_TABLE
Partition table to flash
For example, to flash to ``/dev/ttyUSB2``, use the following command after
having build the application in the ``build`` directory:
.. code-block:: console
west flash -d build/ --skip-rebuild --esp-device /dev/ttyUSB2
References
**********
.. _`ESP32 Technical Reference Manual`: https://espressif.com/sites/default/files/documentation/esp32_technical_reference_manual_en.pdf
.. _`JTAG debugging for ESP32`: http://esp-idf.readthedocs.io/en/latest/api-guides/jtag-debugging/index.html
.. _`toolchain`: https://esp-idf.readthedocs.io/en/latest/get-started/index.html#get-started-setup-toochain
.. _`SDK`: https://esp-idf.readthedocs.io/en/latest/get-started/index.html#get-started-get-esp-idf
.. _`Hardware Reference`: https://esp-idf.readthedocs.io/en/latest/hw-reference/index.html
.. _`esptool documentation`: https://github.com/espressif/esptool/blob/master/README.md
.. _`esptool.py`: https://github.com/espressif/esptool
.. _`ESP-WROVER-32 V3 Getting Started Guide`: https://dl.espressif.com/doc/esp-idf/latest/get-started/get-started-wrover-kit.html
.. _`installing prerequisites`: https://docs.espressif.com/projects/esp-idf/en/latest/esp32/get-started/index.html#step-1-install-prerequisites
.. _`set up the tools`: https://docs.espressif.com/projects/esp-idf/en/latest/esp32/get-started/index.html#step-3-set-up-the-tools
.. _`set up environment variables`: https://docs.espressif.com/projects/esp-idf/en/latest/esp32/get-started/index.html#step-4-set-up-the-environment-variables
.. _`ESP32 Toolchain`: https://docs.espressif.com/projects/esp-idf/en/v4.2/esp32/api-guides/tools/idf-tools.html#xtensa-esp32-elf
.. _`OpenOCD for ESP32 download`: https://docs.espressif.com/projects/esp-idf/en/v4.2/esp32/api-guides/tools/idf-tools.html#openocd-esp32

View file

@ -0,0 +1,29 @@
/*
* Copyright (c) 2022 Espressif Systems (Shanghai) Co., Ltd.
*
* SPDX-License-Identifier: Apache-2.0
*/
/dts-v1/;
#include <espressif/esp32.dtsi>
/ {
model = "esp32_net";
compatible = "espressif,esp32_net";
chosen {
zephyr,sram = &sram0;
};
};
&cpu0 {
clock-frequency = <ESP32_CLK_CPU_240M>;
};
&cpu1 {
clock-frequency = <ESP32_CLK_CPU_240M>;
};
&trng0 {
status = "okay";
};

View file

@ -0,0 +1,13 @@
identifier: esp32_net
name: ESP32_NET
type: mcu
arch: xtensa
toolchain:
- espressif
supported:
- gpio
- i2c
- watchdog
- uart
- pinmux
- nvs

View file

@ -0,0 +1,26 @@
# SPDX-License-Identifier: Apache-2.0
CONFIG_XTENSA_RESET_VECTOR=n
CONFIG_BOARD_ESP32_NET=y
CONFIG_SOC_ESP32_NET=y
CONFIG_MAIN_STACK_SIZE=2048
CONFIG_SYS_CLOCK_HW_CYCLES_PER_SEC=240000000
CONFIG_CONSOLE=n
CONFIG_SERIAL=n
CONFIG_UART_CONSOLE=n
CONFIG_XTENSA_USE_CORE_CRT1=n
CONFIG_PINMUX=n
CONFIG_GPIO=n
CONFIG_GPIO_ESP32=n
CONFIG_GEN_ISR_TABLES=y
CONFIG_GEN_IRQ_VECTOR_TABLE=n
CONFIG_I2C=n
CONFIG_CLOCK_CONTROL=y

View file

@ -0,0 +1,5 @@
set ESP_RTOS none
set ESP32_ONLYCPU 1
source [find interface/ftdi/esp32_devkitj_v1.cfg]
source [find target/esp32.cfg]

View file

@ -9,6 +9,7 @@ set(LINKER ld)
set(BINTOOLS gnu)
set(CROSS_COMPILE_TARGET_xtensa_esp32 xtensa-esp32-elf)
set(CROSS_COMPILE_TARGET_xtensa_esp32_net xtensa-esp32-elf)
set(CROSS_COMPILE_TARGET_xtensa_esp32s2 xtensa-esp32s2-elf)
set(CROSS_COMPILE_TARGET_riscv_esp32c3 riscv32-esp-elf)

View file

@ -31,6 +31,9 @@ config FLASH_BASE_ADDRESS
hex
default $(dt_node_reg_addr_hex,/soc/flash-controller@3ff42000/flash@0)
config ESP32_NETWORK_CORE
bool "Uses the ESP32 APP_CPU as Network dedicated core"
config ESP32_BT_RESERVE_DRAM
hex "Bluetooth controller reserved RAM region"
default 0xdb5c if BT
@ -38,7 +41,8 @@ config ESP32_BT_RESERVE_DRAM
config ESP_HEAP_MEM_POOL_REGION_1_SIZE
int "Internal DRAM region 1 mempool size"
default 16384
default 1024 if ESP32_NETWORK_CORE
default 49152
help
ESP32 has two banks of size 192K and 128K which can be used
as DRAM, system heap allocates area from region 0.

View file

@ -60,6 +60,7 @@ extern void z_sched_ipi(void);
*/
void smp_log(const char *msg)
{
#ifndef CONFIG_ESP32_NETWORK_CORE
k_spinlock_key_t key = k_spin_lock(&loglock);
while (*msg) {
@ -69,6 +70,7 @@ void smp_log(const char *msg)
esp_rom_uart_tx_one_char('\n');
k_spin_unlock(&loglock, key);
#endif
}
static void appcpu_entry2(void)
@ -169,7 +171,7 @@ static void appcpu_entry1(void)
* calls or registers shown are documented, so treat this code with
* extreme caution.
*/
static void appcpu_start(void)
void esp_appcpu_start(void *entry_point)
{
smp_log("ESP32: starting APPCPU");
@ -193,21 +195,11 @@ static void appcpu_start(void)
/* Seems weird that you set the boot address AFTER starting
* the CPU, but this is how they do it...
*/
esp_rom_ets_set_appcpu_boot_addr((void *)appcpu_entry1);
esp_rom_ets_set_appcpu_boot_addr((void *)entry_point);
smp_log("ESP32: APPCPU start sequence complete");
}
IRAM_ATTR static inline uint32_t prid(void)
{
uint32_t id;
__asm__ volatile (
"rsr.prid %0\n"
"extui %0,%0,13,1" : "=r" (id));
return id;
}
IRAM_ATTR static void esp_crosscore_isr(void *arg)
{
ARG_UNUSED(arg);
@ -217,7 +209,7 @@ IRAM_ATTR static void esp_crosscore_isr(void *arg)
z_sched_ipi();
#endif
const int core_id = prid();
const int core_id = esp_core_id();
if (core_id == 0) {
DPORT_WRITE_PERI_REG(DPORT_CPU_INTR_FROM_CPU_0_REG, 0);
@ -250,7 +242,7 @@ void arch_start_cpu(int cpu_num, k_thread_stack_t *stack, int sz,
start_rec = &sr;
appcpu_start();
esp_appcpu_start(appcpu_entry1);
while (!alive_flag) {
}
@ -275,7 +267,7 @@ void arch_start_cpu(int cpu_num, k_thread_stack_t *stack, int sz,
void arch_sched_ipi(void)
{
const int core_id = prid();
const int core_id = esp_core_id();
if (core_id == 0) {
DPORT_WRITE_PERI_REG(DPORT_CPU_INTR_FROM_CPU_0_REG, DPORT_CPU_INTR_FROM_CPU_0);

View file

@ -18,7 +18,11 @@
#include <zephyr/linker/linker-tool.h>
#define RAMABLE_REGION dram0_0_seg
#ifndef CONFIG_ESP32_NETWORK_CORE
#define RAMABLE_REGION_1 dram0_1_seg
#else
#define RAMABLE_REGION_1 dram0_0_seg
#endif
#define RODATA_REGION drom0_0_seg
#define IRAM_REGION iram0_0_seg
#define FLASH_CODE_REGION irom0_0_seg
@ -46,7 +50,13 @@ MEMORY
mcuboot_hdr (RX): org = 0x0, len = 0x20
metadata (RX): org = 0x20, len = 0x20
ROM (RX): org = 0x40, len = ROM_SIZE - 0x40
#ifdef CONFIG_ESP32_NETWORK_CORE
iram0_0_seg(RX): org = 0x40080000, len = 0x10000
#else
iram0_0_seg(RX): org = 0x40080000, len = 0x20000
#endif
irom0_0_seg(RX): org = IROM_SEG_ORG, len = IROM_SEG_LEN
/*
* Following is DRAM memory split with reserved address ranges in ESP32:
@ -61,7 +71,14 @@ MEMORY
* - Utilize available memory regions to full capacity
*/
dram0_0_seg(RW): org = 0x3FFB0000 + CONFIG_ESP32_BT_RESERVE_DRAM, len = 0x2c200 - CONFIG_ESP32_BT_RESERVE_DRAM
#ifdef CONFIG_ESP32_NETWORK_CORE
dram0_shm0_seg(RW): org = 0x3FFE5230, len = 2K /* shared RAM reserved for IPM */
dram0_sem0_seg(RW): org = 0x3FFE5A30, len = 8 /* shared data reserved for IPM data header */
dram0_1_seg(RW): org = 0x3FFE5A38, len = 0K /* for AMP builds dram0_1 is reserved for network core */
#else
dram0_1_seg(RW): org = 0x3FFE5230, len = 0x1BCB0 - 0xEE0 /* skip data for APP CPU initialization usage */
#endif
/* DROM is the first segment placed in generated binary.
* MCUboot binary for ESP32 has image header of 0x20 bytes.

View file

@ -18,6 +18,8 @@
#include <zephyr/types.h>
#include <zephyr/linker/linker-defs.h>
#include <kernel_internal.h>
#include <zephyr/sys/printk.h>
#include <device.h>
#include "esp_private/system_internal.h"
#include "esp32/rom/cache.h"
@ -27,8 +29,51 @@
#include "esp_spi_flash.h"
#include "esp_err.h"
#include "esp32/spiram.h"
#include <zephyr/sys/printk.h>
#include "esp_app_format.h"
extern void z_cstart(void);
#ifdef CONFIG_ESP32_NETWORK_CORE
extern const unsigned char esp32_net_fw_array[];
extern const int esp_32_net_fw_array_size;
void __attribute__((section(".iram1"))) start_esp32_net_cpu(void)
{
esp_image_header_t *header = (esp_image_header_t *)&esp32_net_fw_array[0];
esp_image_segment_header_t *segment =
(esp_image_segment_header_t *)&esp32_net_fw_array[sizeof(esp_image_header_t)];
uint8_t *segment_payload;
uint32_t entry_addr = header->entry_addr;
uint32_t idx = sizeof(esp_image_header_t) + sizeof(esp_image_segment_header_t);
for (int i = 0; i < header->segment_count; i++) {
segment_payload = (uint8_t *)&esp32_net_fw_array[idx];
if (segment->load_addr >= SOC_IRAM_LOW && segment->load_addr < SOC_IRAM_HIGH) {
/* IRAM segment only accepts 4 byte access, avoid memcpy usage here */
volatile uint32_t *src = (volatile uint32_t *)segment_payload;
volatile uint32_t *dst =
(volatile uint32_t *)segment->load_addr;
for (int i = 0; i < segment->data_len/4 ; i++) {
dst[i] = src[i];
}
} else if (segment->load_addr >= SOC_DRAM_LOW &&
segment->load_addr < SOC_DRAM_HIGH) {
memcpy((void *)segment->load_addr,
(const void *)segment_payload,
segment->data_len);
}
idx += segment->data_len;
segment = (esp_image_segment_header_t *)&esp32_net_fw_array[idx];
idx += sizeof(esp_image_segment_header_t);
}
esp_appcpu_start((void *)entry_addr);
}
#endif
/*
* 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
@ -38,7 +83,6 @@ void __attribute__((section(".iram1"))) __esp_platform_start(void)
{
volatile uint32_t *wdt_rtc_protect = (uint32_t *)RTC_CNTL_WDTWPROTECT_REG;
volatile uint32_t *wdt_rtc_reg = (uint32_t *)RTC_CNTL_WDTCONFIG0_REG;
volatile uint32_t *app_cpu_config_reg = (uint32_t *)DPORT_APPCPU_CTRL_B_REG;
extern uint32_t _init_start;
/* Move the exception vector table to IRAM. */
@ -75,6 +119,16 @@ void __attribute__((section(".iram1"))) __esp_platform_start(void)
*wdt_rtc_reg &= ~RTC_CNTL_WDT_EN;
*wdt_rtc_protect = 0;
#if CONFIG_ESP32_NETWORK_CORE
/* start the esp32 network core before
* start zephyr
*/
soc_ll_stall_core(1);
soc_ll_reset_core(1);
DPORT_REG_WRITE(DPORT_APPCPU_CTRL_D_REG, 0);
start_esp32_net_cpu();
#endif
#if CONFIG_ESP_SPIRAM
esp_err_t err = esp_spiram_init();
@ -98,6 +152,7 @@ void __attribute__((section(".iram1"))) __esp_platform_start(void)
spi_flash_guard_set(&g_flash_guard_default_ops);
#endif
esp_intr_initialize();
/* Start Zephyr */
z_cstart();

View file

@ -31,6 +31,16 @@ static inline void esp32_clear_mask32(uint32_t v, uint32_t mem_addr)
sys_write32(sys_read32(mem_addr) & ~v, mem_addr);
}
static inline uint32_t esp_core_id(void)
{
uint32_t id;
__asm__ volatile (
"rsr.prid %0\n"
"extui %0,%0,13,1" : "=r" (id));
return id;
}
extern void esp_rom_intr_matrix_set(int cpu_no, uint32_t model_num, uint32_t intr_num);
extern int esp_rom_gpio_matrix_in(uint32_t gpio, uint32_t signal_index,
@ -47,6 +57,7 @@ extern STATUS esp_rom_uart_rx_one_char(uint8_t *chr);
extern void esp_rom_Cache_Flush(int cpu);
extern void esp_rom_Cache_Read_Enable(int cpu);
extern void esp_rom_ets_set_appcpu_boot_addr(void *addr);
void esp_appcpu_start(void *entry_point);
/* ROM functions which read/write internal i2c control bus for PLL, APLL */
extern uint8_t esp_rom_i2c_readReg(uint8_t block, uint8_t host_id, uint8_t reg_add);

View file

@ -0,0 +1,19 @@
# SPDX-License-Identifier: Apache-2.0
zephyr_sources(
soc.c
)
if(CONFIG_BUILD_OUTPUT_BIN)
set_property(GLOBAL APPEND PROPERTY extra_post_build_commands
COMMAND ${PYTHON_EXECUTABLE} ${ESP_IDF_PATH}/components/esptool_py/esptool/esptool.py
ARGS --chip esp32 elf2image --flash_mode dio --flash_freq 40m
-o ${CMAKE_BINARY_DIR}/zephyr/${CONFIG_KERNEL_BIN_NAME}.bin
${CMAKE_BINARY_DIR}/zephyr/${CONFIG_KERNEL_BIN_NAME}.elf)
set_property(GLOBAL APPEND PROPERTY extra_post_build_commands
COMMAND ${PYTHON_EXECUTABLE} ${ESP_IDF_PATH}/tools/esp_bin2c_array.py
ARGS -i ${CMAKE_BINARY_DIR}/zephyr/${CONFIG_KERNEL_BIN_NAME}.bin
-o ${CMAKE_BINARY_DIR}/zephyr/${CONFIG_KERNEL_BIN_NAME}.c
-a "esp32_net_fw_array")
endif()

View file

@ -0,0 +1,12 @@
# Copyright (c) 2022 Espressif Systems (Shanghai) Co., Ltd.
# SPDX-License-Identifier: Apache-2.0
if SOC_ESP32_NET
config SOC
default "esp32_net"
config MINIMAL_LIBC_OPTIMIZE_STRING_FOR_SIZE
default n
endif

View file

@ -0,0 +1,75 @@
# Copyright (c) 2022 Espressif Systems (Shanghai) Co., Ltd.
# SPDX-License-Identifier: Apache-2.0
config SOC_ESP32_NET
bool "ESP32_NET"
select XTENSA
select CLOCK_CONTROL
select CLOCK_CONTROL_ESP32
select DYNAMIC_INTERRUPTS
if SOC_ESP32_NET
config IDF_TARGET_ESP32
bool "ESP32 as target board"
default y
config ESPTOOLPY_FLASHFREQ_80M
bool
default y
config ESP32_BT_RESERVE_DRAM
hex "Bluetooth controller reserved RAM region"
default 0xdb5c if BT
default 0
choice ESP32_UNIVERSAL_MAC_ADDRESSES
bool "Number of universally administered (by IEEE) MAC address"
default ESP32_UNIVERSAL_MAC_ADDRESSES_FOUR
help
Configure the number of universally administered (by IEEE) MAC addresses.
During initialization, MAC addresses for each network interface are generated or
derived from a single base MAC address. If the number of universal MAC addresses is four,
all four interfaces (WiFi station, WiFi softap, Bluetooth and Ethernet) receive a universally
administered MAC address. These are generated sequentially by adding 0, 1, 2 and 3 (respectively)
to the final octet of the base MAC address. If the number of universal MAC addresses is two,
only two interfaces (WiFi station and Bluetooth) receive a universally administered MAC address.
These are generated sequentially by adding 0 and 1 (respectively) to the base MAC address.
The remaining two interfaces (WiFi softap and Ethernet) receive local MAC addresses.
These are derived from the universal WiFi station and Bluetooth MAC addresses, respectively.
When using the default (Espressif-assigned) base MAC address, either setting can be used.
When using a custom universal MAC address range, the correct setting will depend on the
allocation of MAC addresses in this range (either 2 or 4 per device.)
config ESP32_UNIVERSAL_MAC_ADDRESSES_TWO
bool "Two"
select ESP_MAC_ADDR_UNIVERSE_WIFI_STA
select ESP_MAC_ADDR_UNIVERSE_BT
config ESP32_UNIVERSAL_MAC_ADDRESSES_FOUR
bool "Four"
select ESP_MAC_ADDR_UNIVERSE_WIFI_STA
select ESP_MAC_ADDR_UNIVERSE_WIFI_AP
select ESP_MAC_ADDR_UNIVERSE_BT
select ESP_MAC_ADDR_UNIVERSE_ETH
endchoice # ESP32_UNIVERSAL_MAC_ADDRESSES
config ESP_MAC_ADDR_UNIVERSE_WIFI_AP
bool
config ESP_MAC_ADDR_UNIVERSE_WIFI_STA
bool
config ESP_MAC_ADDR_UNIVERSE_BT
bool
config ESP_MAC_ADDR_UNIVERSE_ETH
bool
config ESP32_UNIVERSAL_MAC_ADDRESSES
int
default 2 if ESP32_UNIVERSAL_MAC_ADDRESSES_TWO
default 4 if ESP32_UNIVERSAL_MAC_ADDRESSES_FOUR
endif # SOC_ESP32

View file

@ -0,0 +1,359 @@
/*
* Copyright (c) 2022 Espressif Systems (Shanghai) Co., Ltd.
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <xtensa/config/core-isa.h>
#include <sys/util.h>
#include <sw_isr_table.h>
#if !defined(XCHAL_INT0_LEVEL) || XCHAL_INT0_LEVEL != 1
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT1_LEVEL) || XCHAL_INT1_LEVEL != 1
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT2_LEVEL) || XCHAL_INT2_LEVEL != 1
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT3_LEVEL) || XCHAL_INT3_LEVEL != 1
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT4_LEVEL) || XCHAL_INT4_LEVEL != 1
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT5_LEVEL) || XCHAL_INT5_LEVEL != 1
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT6_LEVEL) || XCHAL_INT6_LEVEL != 1
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT7_LEVEL) || XCHAL_INT7_LEVEL != 1
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT8_LEVEL) || XCHAL_INT8_LEVEL != 1
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT9_LEVEL) || XCHAL_INT9_LEVEL != 1
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT10_LEVEL) || XCHAL_INT10_LEVEL != 1
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT12_LEVEL) || XCHAL_INT12_LEVEL != 1
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT13_LEVEL) || XCHAL_INT13_LEVEL != 1
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT17_LEVEL) || XCHAL_INT17_LEVEL != 1
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT18_LEVEL) || XCHAL_INT18_LEVEL != 1
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT11_LEVEL) || XCHAL_INT11_LEVEL != 3
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT15_LEVEL) || XCHAL_INT15_LEVEL != 3
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT22_LEVEL) || XCHAL_INT22_LEVEL != 3
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT23_LEVEL) || XCHAL_INT23_LEVEL != 3
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT27_LEVEL) || XCHAL_INT27_LEVEL != 3
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT29_LEVEL) || XCHAL_INT29_LEVEL != 3
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT14_LEVEL) || XCHAL_INT14_LEVEL != 7
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT16_LEVEL) || XCHAL_INT16_LEVEL != 5
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT26_LEVEL) || XCHAL_INT26_LEVEL != 5
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT31_LEVEL) || XCHAL_INT31_LEVEL != 5
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT19_LEVEL) || XCHAL_INT19_LEVEL != 2
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT20_LEVEL) || XCHAL_INT20_LEVEL != 2
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT21_LEVEL) || XCHAL_INT21_LEVEL != 2
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT24_LEVEL) || XCHAL_INT24_LEVEL != 4
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT25_LEVEL) || XCHAL_INT25_LEVEL != 4
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT28_LEVEL) || XCHAL_INT28_LEVEL != 4
#error core-isa.h interrupt level does not match dispatcher!
#endif
#if !defined(XCHAL_INT30_LEVEL) || XCHAL_INT30_LEVEL != 4
#error core-isa.h interrupt level does not match dispatcher!
#endif
static inline int _xtensa_handle_one_int1(unsigned int mask)
{
int irq;
if (mask & 0x7f) {
if (mask & 0x7) {
if (mask & BIT(0)) {
mask = BIT(0);
irq = 0;
goto handle_irq;
}
if (mask & BIT(1)) {
mask = BIT(1);
irq = 1;
goto handle_irq;
}
if (mask & BIT(2)) {
mask = BIT(2);
irq = 2;
goto handle_irq;
}
} else {
if (mask & 0x18) {
if (mask & BIT(3)) {
mask = BIT(3);
irq = 3;
goto handle_irq;
}
if (mask & BIT(4)) {
mask = BIT(4);
irq = 4;
goto handle_irq;
}
} else {
if (mask & BIT(5)) {
mask = BIT(5);
irq = 5;
goto handle_irq;
}
if (mask & BIT(6)) {
mask = BIT(6);
irq = 6;
goto handle_irq;
}
}
}
} else {
if (mask & 0x780) {
if (mask & 0x180) {
if (mask & BIT(7)) {
mask = BIT(7);
irq = 7;
goto handle_irq;
}
if (mask & BIT(8)) {
mask = BIT(8);
irq = 8;
goto handle_irq;
}
} else {
if (mask & BIT(9)) {
mask = BIT(9);
irq = 9;
goto handle_irq;
}
if (mask & BIT(10)) {
mask = BIT(10);
irq = 10;
goto handle_irq;
}
}
} else {
if (mask & 0x3000) {
if (mask & BIT(12)) {
mask = BIT(12);
irq = 12;
goto handle_irq;
}
if (mask & BIT(13)) {
mask = BIT(13);
irq = 13;
goto handle_irq;
}
} else {
if (mask & BIT(17)) {
mask = BIT(17);
irq = 17;
goto handle_irq;
}
if (mask & BIT(18)) {
mask = BIT(18);
irq = 18;
goto handle_irq;
}
}
}
}
return 0;
handle_irq:
_sw_isr_table[irq].isr(_sw_isr_table[irq].arg);
return mask;
}
static inline int _xtensa_handle_one_int3(unsigned int mask)
{
int irq;
if (mask & 0x408800) {
if (mask & BIT(11)) {
mask = BIT(11);
irq = 11;
goto handle_irq;
}
if (mask & BIT(15)) {
mask = BIT(15);
irq = 15;
goto handle_irq;
}
if (mask & BIT(22)) {
mask = BIT(22);
irq = 22;
goto handle_irq;
}
} else {
if (mask & BIT(23)) {
mask = BIT(23);
irq = 23;
goto handle_irq;
}
if (mask & BIT(27)) {
mask = BIT(27);
irq = 27;
goto handle_irq;
}
if (mask & BIT(29)) {
mask = BIT(29);
irq = 29;
goto handle_irq;
}
}
return 0;
handle_irq:
_sw_isr_table[irq].isr(_sw_isr_table[irq].arg);
return mask;
}
static inline int _xtensa_handle_one_int7(unsigned int mask)
{
int irq;
if (mask & BIT(14)) {
mask = BIT(14);
irq = 14;
goto handle_irq;
}
return 0;
handle_irq:
_sw_isr_table[irq].isr(_sw_isr_table[irq].arg);
return mask;
}
static inline int _xtensa_handle_one_int5(unsigned int mask)
{
int irq;
if (mask & BIT(16)) {
mask = BIT(16);
irq = 16;
goto handle_irq;
}
if (mask & BIT(26)) {
mask = BIT(26);
irq = 26;
goto handle_irq;
}
if (mask & BIT(31)) {
mask = BIT(31);
irq = 31;
goto handle_irq;
}
return 0;
handle_irq:
_sw_isr_table[irq].isr(_sw_isr_table[irq].arg);
return mask;
}
static inline int _xtensa_handle_one_int2(unsigned int mask)
{
int irq;
if (mask & BIT(19)) {
mask = BIT(19);
irq = 19;
goto handle_irq;
}
if (mask & BIT(20)) {
mask = BIT(20);
irq = 20;
goto handle_irq;
}
if (mask & BIT(21)) {
mask = BIT(21);
irq = 21;
goto handle_irq;
}
return 0;
handle_irq:
_sw_isr_table[irq].isr(_sw_isr_table[irq].arg);
return mask;
}
static inline int _xtensa_handle_one_int4(unsigned int mask)
{
int irq;
if (mask & 0x3000000) {
if (mask & BIT(24)) {
mask = BIT(24);
irq = 24;
goto handle_irq;
}
if (mask & BIT(25)) {
mask = BIT(25);
irq = 25;
goto handle_irq;
}
} else {
if (mask & BIT(28)) {
mask = BIT(28);
irq = 28;
goto handle_irq;
}
if (mask & BIT(30)) {
mask = BIT(30);
irq = 30;
goto handle_irq;
}
}
return 0;
handle_irq:
_sw_isr_table[irq].isr(_sw_isr_table[irq].arg);
return mask;
}
static inline int _xtensa_handle_one_int0(unsigned int mask)
{
return 0;
}
static inline int _xtensa_handle_one_int6(unsigned int mask)
{
return 0;
}

View file

@ -0,0 +1,21 @@
/*
* Copyright (c) 2021 Intel Corporation.
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <inttypes.h>
#ifndef SOC_XTENSA_ESP32_GDBSTUB_H_
#define SOC_XTENSA_ESP32_GDBSTUB_H_
#ifndef ZEPHYR_INCLUDE_ARCH_XTENSA_GDBSTUB_SYS_H_
#error "Must be included after arch/xtensa/gdbstub.h"
#endif /* ZEPHYR_INCLUDE_ARCH_XTENSA_GDBSTUB_SYS_H_ */
#define SOC_GDB_GPKT_BIN_SIZE 420
#define SOC_GDB_GPKT_HEX_SIZE (SOC_GDB_GPKT_BIN_SIZE * 2)
#define SOC_GDB_REGNO_A1 0x0001
#endif /* SOC_XTENSA_ESP32_GDBSTUB_H_ */

View file

@ -0,0 +1,438 @@
/*
* Copyright (c) 2022 Espressif Systems (Shanghai) Co., Ltd.
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file
* @brief Linker command/script file
*
* Linker script for the Xtensa platform.
*/
#include <devicetree.h>
#include <autoconf.h>
#include <linker/sections.h>
#include <linker/linker-defs.h>
#include <linker/linker-tool.h>
#define RAMABLE_REGION dram0_1_seg :dram0_1_phdr
#define RAMABLE_REGION_1 dram0_1_seg :dram0_1_phdr
#define ROMABLE_REGION dram0_1_seg :dram0_1_phdr
#define IRAM_REGION iram0_0_seg :iram0_0_phdr
#define FLASH_CODE_REGION iram0_0_seg :iram0_0_phdr
MEMORY
{
iram0_0_seg(RX): org = 0x40080000 + 0x10000, len = 0x10000
dram0_shm0_seg(RW): org = 0x3FFE5230, len = 2K /* shared RAM reserved for IPM */
dram0_sem0_seg(RW): org = 0x3FFE5A30, len = 8 /*shared data reserved for IPM data header */
dram0_1_seg(RW): org = 0x3FFE5A38 + CONFIG_ESP32_BT_RESERVE_DRAM, len = 0x1BCB0 - 0xEE0 - CONFIG_ESP32_BT_RESERVE_DRAM
#ifdef CONFIG_GEN_ISR_TABLES
IDT_LIST(RW): org = 0x3ebfe010, len = 0x2000
#endif
}
PHDRS
{
dram0_1_phdr PT_LOAD;
iram0_0_phdr PT_LOAD;
}
/* Default entry point: */
ENTRY(__app_cpu_start)
_rom_store_table = 0;
SECTIONS
{
#include <linker/rel-sections.ld>
/* Send .iram0 code to iram */
.iram0.vectors : ALIGN(4)
{
/* Vectors go to IRAM */
_init_start = ABSOLUTE(.);
/* Vectors according to builds/RF-2015.2-win32/esp108_v1_2_s5_512int_2/config.html */
. = 0x0;
KEEP(*(.WindowVectors.text));
. = 0x180;
KEEP(*(.Level2InterruptVector.text));
. = 0x1c0;
KEEP(*(.Level3InterruptVector.text));
. = 0x200;
KEEP(*(.Level4InterruptVector.text));
. = 0x240;
KEEP(*(.Level5InterruptVector.text));
. = 0x280;
KEEP(*(.DebugExceptionVector.text));
. = 0x2c0;
KEEP(*(.NMIExceptionVector.text));
. = 0x300;
KEEP(*(.KernelExceptionVector.text));
. = 0x340;
KEEP(*(.UserExceptionVector.text));
. = 0x3C0;
KEEP(*(.DoubleExceptionVector.text));
. = 0x400;
*(.*Vector.literal)
*(.UserEnter.literal);
*(.UserEnter.text);
. = ALIGN (16);
*(.entry.text)
*(.init.literal)
*(.init)
_init_end = ABSOLUTE(.);
/* This goes here, not at top of linker script, so addr2line finds it last,
and uses it in preference to the first symbol in IRAM */
_iram_start = ABSOLUTE(0);
} GROUP_LINK_IN(IRAM_REGION)
SECTION_DATA_PROLOGUE(k_objects,, ALIGN(4))
{
Z_LINK_ITERABLE_GC_ALLOWED(k_timer);
. = ALIGN(4);
Z_LINK_ITERABLE_GC_ALLOWED(k_mem_slab);
. = ALIGN(4);
Z_LINK_ITERABLE_GC_ALLOWED(k_mem_pool);
. = ALIGN(4);
Z_LINK_ITERABLE_GC_ALLOWED(k_heap);
. = ALIGN(4);
Z_LINK_ITERABLE_GC_ALLOWED(k_mutex);
. = ALIGN(4);
Z_LINK_ITERABLE_GC_ALLOWED(k_stack);
. = ALIGN(4);
Z_LINK_ITERABLE_GC_ALLOWED(k_msgq);
. = ALIGN(4);
Z_LINK_ITERABLE_GC_ALLOWED(k_mbox);
. = ALIGN(4);
Z_LINK_ITERABLE_GC_ALLOWED(k_pipe);
. = ALIGN(4);
Z_LINK_ITERABLE_GC_ALLOWED(k_sem);
. = ALIGN(4);
Z_LINK_ITERABLE_GC_ALLOWED(k_queue);
} GROUP_DATA_LINK_IN(RAMABLE_REGION, ROMABLE_REGION)
SECTION_DATA_PROLOGUE(net,, ALIGN(4))
{
_esp_net_buf_pool_list = .;
KEEP(*(SORT_BY_NAME("._net_buf_pool.static.*")))
#if defined(CONFIG_NETWORKING)
Z_LINK_ITERABLE_ALIGNED(net_if, 4);
Z_LINK_ITERABLE_ALIGNED(net_if_dev, 4);
Z_LINK_ITERABLE_ALIGNED(net_l2, 4);
#endif
} GROUP_DATA_LINK_IN(RAMABLE_REGION, ROMABLE_REGION)
ITERABLE_SECTION_RAM(_static_thread_data, 4)
#pragma push_macro("ITERABLE_SECTION_RAM")
#pragma push_macro("ITERABLE_SECTION_RAM_GC_ALLOWED")
#undef ITERABLE_SECTION_RAM_GC_ALLOWED
#define ITERABLE_SECTION_RAM_GC_ALLOWED(x, y)
#undef ITERABLE_SECTION_RAM
#define ITERABLE_SECTION_RAM(x, y)
#include <linker/common-ram.ld>
/* Restore original value for symbols referenced by `common-ram.ld` */
_net_buf_pool_list = _esp_net_buf_pool_list;
#pragma pop_macro("ITERABLE_SECTION_RAM_GC_ALLOWED")
#pragma pop_macro("ITERABLE_SECTION_RAM")
.dram0.data :
{
_data_start = ABSOLUTE(.);
_btdm_data_start = ABSOLUTE(.);
*libbtdm_app.a:(.data .data.*)
. = ALIGN (4);
_btdm_data_end = ABSOLUTE(.);
*(.data)
*(.data.*)
*(.gnu.linkonce.d.*)
*(.data1)
*(.sdata)
*(.sdata.*)
*(.gnu.linkonce.s.*)
*(.sdata2)
*(.sdata2.*)
*(.gnu.linkonce.s2.*)
/* rodata for panic handler(libarch__xtensa__core.a) and all
* dependent functions should be placed in DRAM to avoid issue
* when flash cache is disabled */
*libarch__xtensa__core.a:(.rodata .rodata.*)
*libkernel.a:fatal.*(.rodata .rodata.*)
*libkernel.a:init.*(.rodata .rodata.*)
*libzephyr.a:cbprintf_complete*(.rodata .rodata.*)
*libzephyr.a:log_core.*(.rodata .rodata.*)
*libzephyr.a:log_backend_uart.*(.rodata .rodata.*)
*libzephyr.a:log_output.*(.rodata .rodata.*)
*libdrivers__flash.a:flash_esp32.*(.rodata .rodata.*)
*libdrivers__serial.a:uart_esp32.*(.rodata .rodata.*)
. = ALIGN(4);
__esp_log_const_start = .;
KEEP(*(SORT(.log_const_*)));
__esp_log_const_end = .;
. = ALIGN(4);
__esp_log_backends_start = .;
KEEP(*("._log_backend.*"));
__esp_log_backends_end = .;
KEEP(*(.jcr))
*(.dram1 .dram1.*)
_data_end = ABSOLUTE(.);
. = ALIGN(4);
} GROUP_LINK_IN(RAMABLE_REGION)
SECTION_PROLOGUE(_RODATA_SECTION_NAME,,ALIGN(20))
{
_rodata_start = ABSOLUTE(.);
#ifdef CONFIG_USERSPACE
Z_LINK_ITERABLE_ALIGNED(z_object_assignment, 4);
#endif
#if defined(CONFIG_NET_SOCKETS)
Z_LINK_ITERABLE_ALIGNED(net_socket_register, 4);
#endif
#if defined(CONFIG_NET_L2_PPP)
Z_LINK_ITERABLE_ALIGNED(ppp_protocol_handler, 4);
#endif
Z_LINK_ITERABLE_ALIGNED(bt_l2cap_fixed_chan, 4);
#if defined(CONFIG_BT_BREDR)
Z_LINK_ITERABLE_ALIGNED(bt_l2cap_br_fixed_chan, 4);
#endif
#if defined(CONFIG_BT_CONN)
Z_LINK_ITERABLE_ALIGNED(bt_conn_cb, 4)
#endif
Z_LINK_ITERABLE_ALIGNED(bt_gatt_service_static, 4);
#if defined(CONFIG_BT_MESH)
Z_LINK_ITERABLE_ALIGNED(bt_mesh_subnet_cb, 4);
Z_LINK_ITERABLE_ALIGNED(bt_mesh_app_key_cb, 4);
Z_LINK_ITERABLE_ALIGNED(bt_mesh_hb_cb, 4);
#endif
#if defined(CONFIG_BT_MESH_FRIEND)
Z_LINK_ITERABLE_ALIGNED(bt_mesh_friend_cb, 4);
#endif
#if defined(CONFIG_BT_MESH_LOW_POWER)
Z_LINK_ITERABLE_ALIGNED(bt_mesh_lpn_cb, 4);
#endif
#if defined(CONFIG_BT_MESH_PROXY)
Z_LINK_ITERABLE_ALIGNED(bt_mesh_proxy_cb, 4);
#endif
#if defined(CONFIG_EC_HOST_CMD)
Z_LINK_ITERABLE_ALIGNED(ec_host_cmd_handler, 4);
#endif
#if defined(CONFIG_SETTINGS)
Z_LINK_ITERABLE_ALIGNED(settings_handler_static, 4);
#endif
Z_LINK_ITERABLE_ALIGNED(k_p4wq_initparam, 4);
Z_LINK_ITERABLE_ALIGNED(shell, 4);
Z_LINK_ITERABLE_ALIGNED(tracing_backend, 4)
__esp_shell_root_cmds_start = .;
KEEP(*(SORT(.shell_root_cmd_*)));
__esp_shell_root_cmds_end = .;
. = ALIGN(4);
*(.rodata)
*(.rodata.*)
*(.gnu.linkonce.r.*)
*(.rodata1)
__XT_EXCEPTION_TABLE__ = ABSOLUTE(.);
KEEP (*(.xt_except_table))
KEEP (*(.gcc_except_table .gcc_except_table.*))
*(.gnu.linkonce.e.*)
*(.gnu.version_r)
KEEP (*(.eh_frame))
/* C++ constructor and destructor tables, properly ordered: */
KEEP (*crtbegin.o(.ctors))
KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors))
KEEP (*(SORT(.ctors.*)))
KEEP (*(.ctors))
KEEP (*crtbegin.o(.dtors))
KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors))
KEEP (*(SORT(.dtors.*)))
KEEP (*(.dtors))
/* C++ exception handlers table: */
__XT_EXCEPTION_DESCS__ = ABSOLUTE(.);
*(.xt_except_desc)
*(.gnu.linkonce.h.*)
__XT_EXCEPTION_DESCS_END__ = ABSOLUTE(.);
*(.xt_except_desc_end)
*(.dynamic)
*(.gnu.version_d)
. = ALIGN(4); /* this table MUST be 4-byte aligned */
_rodata_end = ABSOLUTE(.);
} GROUP_LINK_IN(ROMABLE_REGION)
#pragma push_macro("ITERABLE_SECTION_ROM")
#pragma push_macro("ROMABLE_REGION")
#undef ITERABLE_SECTION_ROM
#define ITERABLE_SECTION_ROM(x,y)
#undef ROMABLE_REGION
/* This is to workaround limitation of `esptool` which needs single `FLASH` data segment
* which is already defined above. In case, `common-rom.ld` creates additional segments
* they will be placed in DRAM instead. */
#define ROMABLE_REGION RAMABLE_REGION
#include <linker/common-rom.ld>
/* Restore original value for symbols referenced by `common-rom.ld` */
__log_const_start = __esp_log_const_start;
__log_const_end = __esp_log_const_end;
__log_backends_start = __esp_log_backends_start;
__log_backends_end = __esp_log_backends_end;
__shell_root_cmds_start = __esp_shell_root_cmds_start;
__shell_root_cmds_end = __esp_shell_root_cmds_end;
#pragma pop_macro("ROMABLE_REGION")
#pragma pop_macro("ITERABLE_SECTION_ROM")
SECTION_PROLOGUE(_TEXT_SECTION_NAME, , ALIGN(4))
{
/* Code marked as running out of IRAM */
_iram_text_start = ABSOLUTE(.);
*(.iram1 .iram1.*)
*(.iram0.literal .iram.literal .iram.text.literal .iram0.text .iram.text)
*libesp32.a:panic.*(.literal .text .literal.* .text.*)
*librtc.a:(.literal .text .literal.* .text.*)
*libsubsys__net__l2__ethernet.a:(.literal .text .literal.* .text.*)
*libsubsys__net__lib__config.a:(.literal .text .literal.* .text.*)
*libsubsys__net__ip.a:(.literal .text .literal.* .text.*)
*libsubsys__net.a:(.literal .text .literal.* .text.*)
*libarch__xtensa__core.a:(.literal .text .literal.* .text.*)
*libkernel.a:(.literal .text .literal.* .text.*)
*libsoc.a:rtc_*.*(.literal .text .literal.* .text.*)
*libsoc.a:cpu_util.*(.literal .text .literal.* .text.*)
*libgcc.a:lib2funcs.*(.literal .text .literal.* .text.*)
*libdrivers__flash.a:flash_esp32.*(.literal .text .literal.* .text.*)
*libzephyr.a:windowspill_asm.*(.literal .text .literal.* .text.*)
*libzephyr.a:log_noos.*(.literal .text .literal.* .text.*)
*libdrivers__timer.a:xtensa_sys_timer.*(.literal .text .literal.* .text.*)
*libzephyr.a:log_core.*(.literal .text .literal.* .text.*)
*libzephyr.a:cbprintf_complete.*(.literal .text .literal.* .text.*)
*libzephyr.a:printk.*(.literal.printk .literal.vprintk .literal.char_out .text.printk .text.vprintk .text.char_out)
*libzephyr.a:log_msg.*(.literal .text .literal.* .text.*)
*libzephyr.a:log_list.*(.literal .text .literal.* .text.*)
*libdrivers__console.a:uart_console.*(.literal.console_out .text.console_out)
*libzephyr.a:log_output.*(.literal .text .literal.* .text.*)
*libzephyr.a:log_backend_uart.*(.literal .text .literal.* .text.*)
*liblib__libc__minimal.a:string.*(.literal .text .literal.* .text.*)
*libphy.a:( .phyiram .phyiram.*)
*libgcov.a:(.literal .text .literal.* .text.*)
#if defined(CONFIG_ESP32_WIFI_IRAM_OPT)
*libnet80211.a:( .wifi0iram .wifi0iram.* .wifislpiram .wifislpiram.*)
*libpp.a:( .wifi0iram .wifi0iram.* .wifislpiram .wifislpiram.*)
#endif
#if defined(CONFIG_ESP32_WIFI_RX_IRAM_OPT)
*libnet80211.a:( .wifirxiram .wifirxiram.* .wifislprxiram .wifislprxiram.*)
*libpp.a:( .wifirxiram .wifirxiram.* .wifislprxiram .wifislprxiram.*)
#endif
_iram_text_end = ABSOLUTE(.);
. = ALIGN(4);
_iram_end = ABSOLUTE(.);
} GROUP_LINK_IN(IRAM_REGION)
.flash.text :
{
_stext = .;
_text_start = ABSOLUTE(.);
#if !defined(CONFIG_ESP32_WIFI_IRAM_OPT)
*libnet80211.a:( .wifi0iram .wifi0iram.* .wifislpiram .wifislpiram.*)
*libpp.a:( .wifi0iram .wifi0iram.* .wifislpiram .wifislpiram.*)
#endif
#if !defined(CONFIG_ESP32_WIFI_RX_IRAM_OPT)
*libnet80211.a:( .wifirxiram .wifirxiram.* .wifislprxiram .wifislprxiram.*)
*libpp.a:( .wifirxiram .wifirxiram.* .wifislprxiram .wifislprxiram.*)
#endif
*(.literal .text .literal.* .text.*)
_text_end = ABSOLUTE(.);
_etext = .;
/* Similar to _iram_start, this symbol goes here so it is
resolved by addr2line in preference to the first symbol in
the flash.text segment.
*/
_flash_cache_start = ABSOLUTE(0);
} GROUP_LINK_IN(FLASH_CODE_REGION)
/* Shared RAM */
SECTION_DATA_PROLOGUE(_BSS_SECTION_NAME,(NOLOAD),)
{
. = ALIGN (8);
_bss_start = ABSOLUTE(.);
_btdm_bss_start = ABSOLUTE(.);
*libbtdm_app.a:(.bss .bss.* COMMON)
. = ALIGN (4);
_btdm_bss_end = ABSOLUTE(.);
*(.dynsbss)
*(.sbss)
*(.sbss.*)
*(.gnu.linkonce.sb.*)
*(.scommon)
*(.sbss2)
*(.sbss2.*)
*(.gnu.linkonce.sb2.*)
*(.dynbss)
*(.bss)
*(.bss.*)
*(.share.mem)
*(.gnu.linkonce.b.*)
*(COMMON)
. = ALIGN (8);
_bss_end = ABSOLUTE(.);
} GROUP_LINK_IN(RAMABLE_REGION)
ASSERT(((_bss_end - ORIGIN(dram0_1_seg)) <= LENGTH(dram0_1_seg)),
"DRAM segment data does not fit.")
SECTION_DATA_PROLOGUE(_NOINIT_SECTION_NAME, (NOLOAD),)
{
. = ALIGN (8);
*(.noinit)
*(".noinit.*")
. = ALIGN (8);
} GROUP_LINK_IN(RAMABLE_REGION_1)
#ifdef CONFIG_GEN_ISR_TABLES
#include <linker/intlist.ld>
#endif
#include <linker/debug-sections.ld>
SECTION_PROLOGUE(.xtensa.info, 0,)
{
*(.xtensa.info)
}
}
ASSERT(((_iram_end - ORIGIN(iram0_0_seg)) <= LENGTH(iram0_0_seg)),
"IRAM0 segment data does not fit.")

155
soc/xtensa/esp32_net/soc.c Normal file
View file

@ -0,0 +1,155 @@
/*
* Copyright (c) 2022 Espressif Systems (Shanghai) Co., Ltd.
*
* SPDX-License-Identifier: Apache-2.0
*/
/* Include esp-idf headers first to avoid redefining BIT() macro */
#include <drivers/interrupt_controller/intc_esp32.h>
#include <soc.h>
#include <kernel_structs.h>
#include <string.h>
#include <toolchain/gcc.h>
#include <zephyr/types.h>
#include <zephyr.h>
#include "sys/printk.h"
#include <soc/rtc_cntl_reg.h>
#include <soc/timer_group_reg.h>
#include "esp_private/system_internal.h"
#include "esp32/rom/cache.h"
#include "hal/soc_ll.h"
#include "soc/cpu.h"
#include "soc/gpio_periph.h"
#include "esp_spi_flash.h"
#include "esp_err.h"
extern void z_cstart(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 __app_cpu_start(void)
{
extern uint32_t _init_start;
extern uint32_t _bss_start;
extern uint32_t _bss_end;
/* Move the exception vector table to IRAM. */
__asm__ __volatile__ (
"wsr %0, vecbase"
:
: "r"(&_init_start));
/* Zero out BSS. Clobber _bss_start to avoid memset() elision. */
(void)memset(&_bss_start, 0,
(&_bss_end - &_bss_start) * sizeof(_bss_start));
__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
* arch_kernel_init() is invoked.
*/
__asm__ volatile("wsr.MISC0 %0; rsync" : : "r"(&_kernel.cpus[0]));
esp_intr_initialize();
/* Start Zephyr */
z_cstart();
CODE_UNREACHABLE;
}
/* Boot-time static default printk handler, possibly to be overridden later. */
int IRAM_ATTR arch_printk_char_out(int c)
{
if (c == '\n') {
esp_rom_uart_tx_one_char('\r');
}
esp_rom_uart_tx_one_char(c);
return 0;
}
void sys_arch_reboot(int type)
{
esp_restart_noos();
}
void IRAM_ATTR esp_restart_noos(void)
{
/* Disable interrupts */
z_xt_ints_off(0xFFFFFFFF);
const uint32_t core_id = cpu_hal_get_core_id();
const uint32_t other_core_id = (core_id == 0) ? 1 : 0;
soc_ll_reset_core(other_core_id);
soc_ll_stall_core(other_core_id);
/* Flush any data left in UART FIFOs */
esp_rom_uart_tx_wait_idle(0);
esp_rom_uart_tx_wait_idle(1);
esp_rom_uart_tx_wait_idle(2);
/* Disable cache */
Cache_Read_Disable(0);
Cache_Read_Disable(1);
/* 2nd stage bootloader reconfigures SPI flash signals. */
/* Reset them to the defaults expected by ROM */
WRITE_PERI_REG(GPIO_FUNC0_IN_SEL_CFG_REG, 0x30);
WRITE_PERI_REG(GPIO_FUNC1_IN_SEL_CFG_REG, 0x30);
WRITE_PERI_REG(GPIO_FUNC2_IN_SEL_CFG_REG, 0x30);
WRITE_PERI_REG(GPIO_FUNC3_IN_SEL_CFG_REG, 0x30);
WRITE_PERI_REG(GPIO_FUNC4_IN_SEL_CFG_REG, 0x30);
WRITE_PERI_REG(GPIO_FUNC5_IN_SEL_CFG_REG, 0x30);
/* Reset wifi/bluetooth/ethernet/sdio (bb/mac) */
DPORT_SET_PERI_REG_MASK(DPORT_CORE_RST_EN_REG,
DPORT_BB_RST | DPORT_FE_RST | DPORT_MAC_RST |
DPORT_BT_RST | DPORT_BTMAC_RST |
DPORT_SDIO_RST | DPORT_SDIO_HOST_RST |
DPORT_EMAC_RST | DPORT_MACPWR_RST |
DPORT_RW_BTMAC_RST | DPORT_RW_BTLP_RST);
DPORT_REG_WRITE(DPORT_CORE_RST_EN_REG, 0);
/* Reset timer/spi/uart */
DPORT_SET_PERI_REG_MASK(
DPORT_PERIP_RST_EN_REG,
/* UART TX FIFO cannot be reset correctly on ESP32, */
/* so reset the UART memory by DPORT here. */
DPORT_TIMERS_RST | DPORT_SPI01_RST | DPORT_UART_RST |
DPORT_UART1_RST | DPORT_UART2_RST | DPORT_UART_MEM_RST);
DPORT_REG_WRITE(DPORT_PERIP_RST_EN_REG, 0);
/* Clear entry point for APP CPU */
DPORT_REG_WRITE(DPORT_APPCPU_CTRL_D_REG, 0);
/* Reset CPUs */
if (core_id == 0) {
/* Running on PRO CPU: APP CPU is stalled. Can reset both CPUs. */
soc_ll_reset_core(1);
soc_ll_reset_core(0);
} else {
/* Running on APP CPU: need to reset PRO CPU and unstall it, */
/* then reset APP CPU */
soc_ll_reset_core(0);
soc_ll_stall_core(0);
soc_ll_reset_core(1);
}
while (true) {
;
}
}

View file

@ -0,0 +1,69 @@
/*
* Copyright (c) 2022 Espressif Systems (Shanghai) Co., Ltd.
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef __SOC_H__
#define __SOC_H__
#include <soc/dport_reg.h>
#include <soc/rtc_cntl_reg.h>
#include <soc/soc_caps.h>
#include <esp32/rom/ets_sys.h>
#include <esp32/rom/spi_flash.h>
#include <zephyr/types.h>
#include <stdbool.h>
#include <arch/xtensa/arch.h>
#include <xtensa/core-macros.h>
#include <esp32/clk.h>
void __esp_platform_start(void);
static inline void esp32_set_mask32(uint32_t v, uint32_t mem_addr)
{
sys_write32(sys_read32(mem_addr) | v, mem_addr);
}
static inline void esp32_clear_mask32(uint32_t v, uint32_t mem_addr)
{
sys_write32(sys_read32(mem_addr) & ~v, mem_addr);
}
static inline uint32_t esp_core_id(void)
{
uint32_t id;
__asm__ volatile (
"rsr.prid %0\n"
"extui %0,%0,13,1" : "=r" (id));
return id;
}
extern void esp_rom_intr_matrix_set(int cpu_no, uint32_t model_num, uint32_t intr_num);
extern int esp_rom_gpio_matrix_in(uint32_t gpio, uint32_t signal_index,
bool inverted);
extern int esp_rom_gpio_matrix_out(uint32_t gpio, uint32_t signal_index,
bool out_inverted,
bool out_enabled_inverted);
extern void esp_rom_uart_attach(void);
extern void esp_rom_uart_tx_wait_idle(uint8_t uart_no);
extern STATUS esp_rom_uart_tx_one_char(uint8_t chr);
extern STATUS esp_rom_uart_rx_one_char(uint8_t *chr);
extern void esp_rom_Cache_Flush(int cpu);
extern void esp_rom_Cache_Read_Enable(int cpu);
extern void esp_rom_ets_set_appcpu_boot_addr(void *addr);
/* ROM functions which read/write internal i2c control bus for PLL, APLL */
extern uint8_t esp_rom_i2c_readReg(uint8_t block, uint8_t host_id, uint8_t reg_add);
extern void esp_rom_i2c_writeReg(uint8_t block, uint8_t host_id, uint8_t reg_add, uint8_t data);
/* ROM information related to SPI Flash chip timing and device */
extern esp_rom_spiflash_chip_t g_rom_flashchip;
extern uint8_t g_rom_spiflash_dummy_len_plus[];
#endif /* __SOC_H__ */

View file

@ -23,6 +23,10 @@
void __esp_platform_start(void);
static inline uint32_t esp_core_id(void)
{
return 0;
}
extern void esp_rom_uart_attach(void);
extern void esp_rom_uart_tx_wait_idle(uint8_t uart_no);
extern STATUS esp_rom_uart_tx_one_char(uint8_t chr);