boards: esp32: add XIP support and enable bootloader build

Disable RTC WDT enabled (by default) by 2nd stage bootloader in ESP-IDF.
This WDT timer ensures correct hand-over and startup sequence from
bootloader to application.

Enabling bootloader caused system clock initialization to fail
when clock rate is greater then 80MHz. This also fixes
esp32 clock source code.

Signed-off-by: Mahavir Jain <mahavir@espressif.com>
This commit is contained in:
Mahavir Jain 2020-08-03 20:23:18 +05:30 committed by Anas Nashif
commit 29f87c3a0f
11 changed files with 154 additions and 26 deletions

View file

@ -30,3 +30,5 @@ CONFIG_I2C_ESP32=y
CONFIG_I2C_0=y
CONFIG_I2C_1=y
CONFIG_CLOCK_CONTROL=y
CONFIG_BOOTLOADER_ESP_IDF=y

View file

@ -7,7 +7,10 @@
#define DT_DRV_COMPAT espressif_esp32_rtc
#include <dt-bindings/clock/esp32_clock.h>
#include <esp_bit_defs.h>
#include <soc/dport_reg.h>
#include <esp32/rom/uart.h>
#include <esp32/rom/rtc.h>
#include <soc/rtc.h>
#include <soc/rtc_cntl_reg.h>
#include <drivers/uart.h>
@ -156,6 +159,7 @@ static void bbpll_configure(rtc_xtal_freq_t xtal_freq, uint32_t pll_freq)
/* Configure the voltage */
REG_SET_FIELD(RTC_CNTL_REG, RTC_CNTL_DIG_DBIAS_WAK, dbias_wak);
esp32_rom_ets_delay_us(DELAY_PLL_DBIAS_RAISE);
I2C_WRITEREG_RTC(I2C_BBPLL, I2C_BBPLL_ENDIV5, cfg->endiv5);
I2C_WRITEREG_RTC(I2C_BBPLL, I2C_BBPLL_BBADC_DSMP, cfg->bbadc_dsmp);
@ -167,6 +171,39 @@ static void bbpll_configure(rtc_xtal_freq_t xtal_freq, uint32_t pll_freq)
I2C_WRITEREG_RTC(I2C_BBPLL, I2C_BBPLL_OC_DCUR, ((bb_cfg->bw << 6) | bb_cfg->dcur));
}
static inline uint32_t clk_val_to_reg_val(uint32_t val)
{
return (val & UINT16_MAX) | ((val & UINT16_MAX) << 16);
}
void IRAM_ATTR ets_update_cpu_frequency(uint32_t ticks_per_us)
{
/* Update scale factors used by ets_delay_us */
esp32_rom_g_ticks_per_us_pro = ticks_per_us;
esp32_rom_g_ticks_per_us_app = ticks_per_us;
}
static void esp32_cpu_freq_to_xtal(int freq, int div)
{
ets_update_cpu_frequency(freq);
uint32_t apb_freq = MHZ(freq);
WRITE_PERI_REG(RTC_APB_FREQ_REG, clk_val_to_reg_val(apb_freq >> 12));
/* set divider from XTAL to APB clock */
REG_SET_FIELD(APB_CTRL_SYSCLK_CONF_REG, APB_CTRL_PRE_DIV_CNT, div - 1);
/* adjust ref_tick */
REG_WRITE(APB_CTRL_XTAL_TICK_CONF_REG, MHZ(freq) / REF_CLK_FREQ - 1);
/* switch clock source */
REG_SET_FIELD(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_SOC_CLK_SEL, RTC_CNTL_SOC_CLK_SEL_XTL);
/* lower the voltage */
if (freq <= 2) {
REG_SET_FIELD(RTC_CNTL_REG, RTC_CNTL_DIG_DBIAS_WAK, DIG_DBIAS_2M);
} else {
REG_SET_FIELD(RTC_CNTL_REG, RTC_CNTL_DIG_DBIAS_WAK, DIG_DBIAS_XTAL);
}
}
static void cpuclk_pll_configure(uint32_t xtal_freq, uint32_t cpu_freq)
{
uint32_t pll_freq = RTC_PLL_FREQ_320M;
@ -194,6 +231,8 @@ static void cpuclk_pll_configure(uint32_t xtal_freq, uint32_t cpu_freq)
/* Set PLL as CPU Clock Source */
REG_SET_FIELD(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_SOC_CLK_SEL, RTC_CNTL_SOC_CLK_SEL_PLL);
ets_update_cpu_frequency(cpu_freq);
/*
* Update REF_Tick,
* if PLL is the cpu clock source, APB frequency is always 80MHz
@ -280,6 +319,7 @@ static int clock_control_esp32_init(const struct device *dev)
REG_SET_FIELD(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_SOC_CLK_SEL, RTC_CNTL_SOC_CLK_SEL_XTL);
break;
case ESP32_CLK_SRC_PLL:
esp32_cpu_freq_to_xtal(xtal_freq[cfg->xtal_freq_sel], 1);
cpuclk_pll_configure(cfg->xtal_freq_sel, cfg->cpu_freq);
break;
default:

View file

@ -31,10 +31,17 @@
* Get voltage level for CPU to run at 240 MHz, or for flash/PSRAM to run at 80 MHz.
* 0x0: level 7; 0x1: level 6; 0x2: level 5; 0x3: level 4. (RO)
*/
#define GET_HP_VOLTAGE (RTC_CNTL_DBIAS_1V25 - ((EFUSE_BLK0_RDATA5_REG >> 22) & 0x3))
#define DIG_DBIAS_240M GET_HP_VOLTAGE
#define DIG_DBIAS_80M_160M RTC_CNTL_DBIAS_1V10 /* FIXME: This macro should be GET_HP_VOLTAGE in case of 80Mhz flash frequency */
#define DIG_DBIAS_XTAL RTC_CNTL_DBIAS_1V10
#define RTC_CNTL_DBIAS_HP_VOLT (RTC_CNTL_DBIAS_1V25 - (REG_GET_FIELD(EFUSE_BLK0_RDATA5_REG, EFUSE_RD_VOL_LEVEL_HP_INV)))
#ifdef CONFIG_ESPTOOLPY_FLASHFREQ_80M
#define DIG_DBIAS_80M_160M RTC_CNTL_DBIAS_HP_VOLT
#else
#define DIG_DBIAS_80M_160M RTC_CNTL_DBIAS_1V10
#endif
#define DIG_DBIAS_240M RTC_CNTL_DBIAS_HP_VOLT
#define DIG_DBIAS_XTAL RTC_CNTL_DBIAS_1V10
#define DIG_DBIAS_2M RTC_CNTL_DBIAS_1V00
#define DELAY_PLL_DBIAS_RAISE 3
/**
* Register definitions for digital PLL (BBPLL)
@ -65,4 +72,8 @@
#define BBPLL_OC_ENB_VCON_VAL 0x00
#define BBPLL_BBADC_CAL_7_0_VAL 0x00
extern uint32_t esp32_rom_g_ticks_per_us_pro;
extern uint32_t esp32_rom_g_ticks_per_us_app;
extern void esp32_rom_ets_delay_us(uint32_t us);
#endif /* ZEPHYR_DRIVERS_CLOCK_CONTROL_ESP32_CLOCK_H_ */

View file

@ -9,7 +9,7 @@
/* Include esp-idf headers first to avoid redefining BIT() macro */
#include <soc/dport_reg.h>
#include <soc/i2c_reg.h>
#include <rom/gpio.h>
#include <esp32/rom/gpio.h>
#include <soc/gpio_sig_map.h>
#include <soc.h>

View file

@ -93,6 +93,7 @@ static int pinmux_set(const struct device *dev, uint32_t pin, uint32_t func)
static int pinmux_get(const struct device *dev, uint32_t pin, uint32_t *func)
{
ARG_UNUSED(dev);
volatile uint32_t *reg = reg_for_pin(pin);
if (!reg) {
@ -101,12 +102,13 @@ static int pinmux_get(const struct device *dev, uint32_t pin, uint32_t *func)
*func = (*reg & MCU_SEL_M) >> MCU_SEL_S;
ARG_UNUSED(dev);
return 0;
}
static int pinmux_pullup(const struct device *dev, uint32_t pin, uint8_t func)
{
ARG_UNUSED(dev);
switch (func) {
case PINMUX_PULLUP_DISABLE:
return set_reg(pin, FUN_PU, FUN_PD);
@ -114,13 +116,14 @@ static int pinmux_pullup(const struct device *dev, uint32_t pin, uint8_t func)
return set_reg(pin, FUN_PD, FUN_PU);
}
ARG_UNUSED(dev);
return -EINVAL;
}
#define CFG(id) ((GPIO_ ## id ## _REG) & 0xff)
static int pinmux_input(const struct device *dev, uint32_t pin, uint8_t func)
{
ARG_UNUSED(dev);
static const uint8_t offs[2][3] = {
{ CFG(ENABLE1_W1TC), CFG(ENABLE1_W1TS), 32 },
{ CFG(ENABLE_W1TC), CFG(ENABLE_W1TS), 0 },
@ -153,7 +156,6 @@ static int pinmux_input(const struct device *dev, uint32_t pin, uint8_t func)
*reg = BIT(pin - line[2]);
ARG_UNUSED(dev);
return 0;
}
#undef CFG
@ -167,13 +169,17 @@ static struct pinmux_driver_api api_funcs = {
static int pinmux_initialize(const struct device *device)
{
ARG_UNUSED(device);
#if !CONFIG_BOOTLOADER_ESP_IDF
uint32_t pin;
for (pin = 0U; pin < ARRAY_SIZE(pin_mux_off); pin++) {
pinmux_set(NULL, pin, 0);
}
ARG_UNUSED(device);
#endif
return 0;
}

View file

@ -9,7 +9,7 @@
/* Include esp-idf headers first to avoid redefining BIT() macro */
#include <esp_intr_alloc.h>
#include <soc/dport_reg.h>
#include <rom/gpio.h>
#include <esp32/rom/gpio.h>
#include <soc/gpio_sig_map.h>
#include <soc/ledc_reg.h>

View file

@ -7,10 +7,10 @@
#define DT_DRV_COMPAT espressif_esp32_uart
/* Include esp-idf headers first to avoid redefining BIT() macro */
#include <rom/ets_sys.h>
#include <esp32/rom/ets_sys.h>
#include <soc/dport_reg.h>
#include <rom/gpio.h>
#include <esp32/rom/gpio.h>
#include <soc/gpio_sig_map.h>

View file

@ -6,3 +6,13 @@ config SOC_ESP32
select XTENSA
select CLOCK_CONTROL
select CLOCK_CONTROL_ESP32
config IDF_TARGET_ESP32
bool "ESP32 as target board"
default y
depends on SOC_ESP32
config ESPTOOLPY_FLASHFREQ_80M
bool
default y
depends on SOC_ESP32

View file

@ -19,14 +19,23 @@
#define RAMABLE_REGION dram0_0_seg :dram0_0_phdr
#define ROMABLE_REGION iram0_0_seg :iram0_0_phdr
#define FLASH_CODE_REGION irom0_0_seg :irom0_0_phdr
#define FLASH_DATA_REGION drom0_0_seg :drom0_0_phdr
PROVIDE ( __stack = 0x3ffe3f20 );
/* Global symbols required for espressif hal build */
PROVIDE ( ets_printf = 0x40007d54 );
PROVIDE ( intr_matrix_set = 0x4000681c );
PROVIDE ( g_ticks_per_us_app = 0x3ffe40f0 );
PROVIDE ( g_ticks_per_us_pro = 0x3ffe01e0 );
PROVIDE ( ets_delay_us = 0x40008534 );
PROVIDE ( esp32_rom_uart_tx_one_char = 0x40009200 );
PROVIDE ( esp32_rom_uart_rx_one_char = 0x400092d0 );
PROVIDE ( esp32_rom_uart_attach = 0x40008fd0 );
PROVIDE ( esp32_rom_uart_tx_wait_idle = 0x40009278 );
PROVIDE ( esp32_rom_intr_matrix_set = 0x4000681c );
PROVIDE ( esp32_rom_intr_matrix_set = intr_matrix_set );
PROVIDE ( esp32_rom_gpio_matrix_in = 0x40009edc );
PROVIDE ( esp32_rom_gpio_matrix_out = 0x40009f0c );
PROVIDE ( esp32_rom_Cache_Flush = 0x40009a14 );
@ -34,13 +43,17 @@ PROVIDE ( esp32_rom_Cache_Read_Enable = 0x40009a84 );
PROVIDE ( esp32_rom_ets_set_appcpu_boot_addr = 0x4000689c );
PROVIDE ( esp32_rom_i2c_readReg = 0x40004148 );
PROVIDE ( esp32_rom_i2c_writeReg = 0x400041a4 );
PROVIDE ( esp32_rom_ets_printf = ets_printf );
PROVIDE ( esp32_rom_g_ticks_per_us_app = g_ticks_per_us_app );
PROVIDE ( esp32_rom_g_ticks_per_us_pro = g_ticks_per_us_app );
PROVIDE ( esp32_rom_ets_delay_us = ets_delay_us );
MEMORY
{
iram0_0_seg(RX): org = 0x40080000, len = 0x20000
iram0_2_seg(RX): org = 0x400D0018, len = 0x330000
irom0_0_seg(RX): org = 0x400D0020, len = 0x330000-0x20
dram0_0_seg(RW): org = 0x3FFB0000, len = 0x50000
drom0_0_seg(R): org = 0x3F400010, len = 0x800000
drom0_0_seg(R): org = 0x3F400020, len = 0x400000-0x20
rtc_iram_seg(RWX): org = 0x400C0000, len = 0x2000
rtc_slow_seg(RW): org = 0x50000000, len = 0x1000
#ifdef CONFIG_GEN_ISR_TABLES
@ -50,8 +63,10 @@ MEMORY
PHDRS
{
iram0_0_phdr PT_LOAD;
drom0_0_phdr PT_LOAD;
dram0_0_phdr PT_LOAD;
iram0_0_phdr PT_LOAD;
irom0_0_phdr PT_LOAD;
}
/* Default entry point: */
@ -221,7 +236,18 @@ SECTIONS
_iram_text_start = ABSOLUTE(.);
*(.iram1 .iram1.*)
*(.iram0.literal .iram.literal .iram.text.literal .iram0.text .iram.text)
*(.literal .text .literal.* .text.*)
*libesp32.a:panic.*(.literal .text .literal.* .text.*)
*librtc.a:(.literal .text .literal.* .text.*)
*libsoc.a:rtc_*.*(.literal .text .literal.* .text.*)
*libsoc.a:cpu_util.*(.literal .text .literal.* .text.*)
*libhal.a:(.literal .text .literal.* .text.*)
*libgcc.a:lib2funcs.*(.literal .text .literal.* .text.*)
*libspi_flash.a:spi_flash_rom_patch.*(.literal .text .literal.* .text.*)
*libgcov.a:(.literal .text .literal.* .text.*)
*libnet80211.a:( .wifi0iram .wifi0iram.*)
*libpp.a:( .wifi0iram .wifi0iram.*)
*libnet80211.a:( .wifirxiram .wifirxiram.*)
*libpp.a:( .wifirxiram .wifirxiram.*)
_iram_text_end = ABSOLUTE(.);
} GROUP_LINK_IN(ROMABLE_REGION)
@ -244,7 +270,7 @@ SECTIONS
. = ALIGN(4);
} GROUP_LINK_IN(RAMABLE_REGION)
SECTION_PROLOGUE(_RODATA_SECTION_NAME,,ALIGN(4))
SECTION_PROLOGUE(_RODATA_SECTION_NAME,,ALIGN(16))
{
_rodata_start = ABSOLUTE(.);
*(.rodata)
@ -276,8 +302,23 @@ SECTIONS
*(.gnu.version_d)
. = ALIGN(4); /* this table MUST be 4-byte aligned */
_rodata_end = ABSOLUTE(.);
} GROUP_LINK_IN(RAMABLE_REGION)
} GROUP_LINK_IN(FLASH_DATA_REGION)
.flash.text :
{
_stext = .;
_text_start = ABSOLUTE(.);
*(.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),)

View file

@ -25,8 +25,8 @@ extern void z_cstart(void);
*/
void __attribute__((section(".iram1"))) __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 *wdt_timg_reg = (uint32_t *)TIMG_WDTCONFIG0_REG(0);
volatile uint32_t *app_cpu_config_reg = (uint32_t *)DPORT_APPCPU_CTRL_B_REG;
extern uint32_t _init_start;
extern uint32_t _bss_start;
@ -47,11 +47,22 @@ void __attribute__((section(".iram1"))) __start(void)
: "g"(&_bss_start)
: "memory");
/* The watchdog timer is enabled in the bootloader. We're done booting,
* so disable it.
#if !CONFIG_BOOTLOADER_ESP_IDF
/* The watchdog timer is enabled in the 1st stage (ROM) bootloader.
* We're done booting, so disable it.
* If 2nd stage bootloader from IDF is enabled, then that will take
* care of this.
*/
volatile uint32_t *wdt_timg_protect = (uint32_t *)TIMG_WDTWPROTECT_REG(0);
volatile uint32_t *wdt_timg_reg = (uint32_t *)TIMG_WDTCONFIG0_REG(0);
*wdt_rtc_protect = RTC_CNTL_WDT_WKEY_VALUE;
*wdt_rtc_reg &= ~RTC_CNTL_WDT_FLASHBOOT_MOD_EN;
*wdt_rtc_protect = 0;
*wdt_timg_protect = TIMG_WDT_WKEY_VALUE;
*wdt_timg_reg &= ~TIMG_WDT_FLASHBOOT_MOD_EN;
*wdt_timg_protect = 0;
#endif
/* Disable normal interrupts. */
__asm__ __volatile__ (
@ -68,6 +79,15 @@ void __attribute__((section(".iram1"))) __start(void)
*/
__asm__ volatile("wsr.MISC0 %0; rsync" : : "r"(&_kernel.cpus[0]));
#if CONFIG_BOOTLOADER_ESP_IDF
/* 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_rtc_protect = RTC_CNTL_WDT_WKEY_VALUE;
*wdt_rtc_reg &= ~RTC_CNTL_WDT_EN;
*wdt_rtc_protect = 0;
#endif
/* Start Zephyr */
z_cstart();

View file

@ -8,7 +8,7 @@
#define __SOC_H__
#include <soc/dport_reg.h>
#include <soc/rtc_cntl_reg.h>
#include <rom/ets_sys.h>
#include <esp32/rom/ets_sys.h>
#include <zephyr/types.h>
#include <stdbool.h>
@ -24,9 +24,7 @@ static inline void esp32_clear_mask32(uint32_t v, uint32_t mem_addr)
sys_write32(sys_read32(mem_addr) & ~v, mem_addr);
}
extern int esp32_rom_intr_matrix_set(int cpu_no,
int interrupt_src,
int interrupt_line);
extern void esp32_rom_intr_matrix_set(int cpu_no, uint32_t model_num, uint32_t intr_num);
extern int esp32_rom_gpio_matrix_in(uint32_t gpio, uint32_t signal_index,
bool inverted);