This is an automated email from the ASF dual-hosted git repository.

linguini pushed a commit to branch master
in repository https://gitbox.apache.org/repos/asf/nuttx.git

commit 680766d304071a590f76adb1e6d9b81189940a40
Author: Filipe Cavalcanti <[email protected]>
AuthorDate: Thu Sep 25 17:06:44 2025 -0300

    arch/xtensa: update SPI Flash driver for ESP32-S2|S3
    
    Updates the SPI Flash driver used for user storage MTD.
    Moves ESP32 and ESP32S3 to use common driver.
    Updates KConfig options to keep backwards compatibility.
    
    Signed-off-by: Filipe Cavalcanti <[email protected]>
---
 arch/xtensa/src/common/espressif/Kconfig           |  33 +-
 arch/xtensa/src/common/espressif/Make.defs         |   1 +
 arch/xtensa/src/common/espressif/esp_spiflash.c    | 621 ++++++---------------
 arch/xtensa/src/common/espressif/esp_spiflash.h    |  91 +--
 .../xtensa/src/common/espressif/esp_spiflash_mtd.c |  88 +--
 arch/xtensa/src/esp32/Kconfig                      |   1 +
 arch/xtensa/src/esp32/Make.defs                    |  15 +-
 arch/xtensa/src/esp32/esp32_ble_adapter.c          |  18 +-
 arch/xtensa/src/esp32/esp32_spiram.c               |  11 +-
 arch/xtensa/src/esp32/esp32_user.c                 |  20 +-
 arch/xtensa/src/esp32/hal.mk                       |  37 +-
 arch/xtensa/src/esp32s2/Make.defs                  |   2 +-
 arch/xtensa/src/esp32s2/hal.mk                     |  30 +-
 arch/xtensa/src/esp32s3/Kconfig                    |   4 +-
 arch/xtensa/src/esp32s3/Make.defs                  |  14 +-
 arch/xtensa/src/esp32s3/esp32s3_ble_adapter.c      |  20 +-
 arch/xtensa/src/esp32s3/esp32s3_spi_timing.c       |   1 -
 arch/xtensa/src/esp32s3/esp32s3_start.c            |   9 +-
 arch/xtensa/src/esp32s3/esp32s3_user.c             |  13 +-
 arch/xtensa/src/esp32s3/hal.mk                     |  36 +-
 .../xtensa/esp32/common/scripts/esp32_sections.ld  |  62 +-
 boards/xtensa/esp32/common/scripts/flat_memory.ld  |   6 +-
 boards/xtensa/esp32/common/scripts/kernel-space.ld |  25 +-
 .../xtensa/esp32/common/src/esp32_board_spiflash.c |  13 +-
 .../esp32/esp32-devkitc/configs/spiflash/defconfig |   5 +-
 .../esp32s2/common/scripts/esp32s2_sections.ld     |  33 +-
 .../esp32s2/common/src/esp32s2_board_spiflash.c    |  12 +-
 boards/xtensa/esp32s3/common/Kconfig               |   2 +-
 .../esp32s3/common/scripts/esp32s3_sections.ld     |  28 +
 .../esp32s3/common/src/esp32s3_board_spiflash.c    |  24 +-
 .../esp32s3-devkit/configs/spiflash/defconfig      |   3 +-
 31 files changed, 558 insertions(+), 720 deletions(-)

diff --git a/arch/xtensa/src/common/espressif/Kconfig 
b/arch/xtensa/src/common/espressif/Kconfig
index 75be260a406..f4bfeff7977 100644
--- a/arch/xtensa/src/common/espressif/Kconfig
+++ b/arch/xtensa/src/common/espressif/Kconfig
@@ -191,9 +191,14 @@ config ESPRESSIF_SPI_BITBANG
                Software implemented SPI peripheral with GPIOs. Suggested to 
use if SPI peripherals are already in use.
 
 config ESPRESSIF_SPIFLASH
-       bool "SPI Flash"
-       depends on ARCH_CHIP_ESP32S2
+       bool "SPI Flash (User Storage)"
        default n
+       depends on !ESP32_PARTITION_TABLE && !ESP32S3_PARTITION_TABLE && 
!ESP32S3_SPIRAM
+       ---help---
+               Enable SPI Flash driver for general storage support. This allows
+               mounting an MTD partition at a configurable region in flash.
+               When using partition table on SPIRAM, legacy drivers for SPI 
Flash
+               used instead, making this option not available.
 
 config ESPRESSIF_DEDICATED_GPIO
        bool "Dedicated GPIO"
@@ -1151,7 +1156,7 @@ endif
 
 if ESPRESSIF_SPIFLASH
 
-comment "General storage MTD configuration"
+comment "User Storage MTD Configuration"
 
 config ESPRESSIF_MTD
        bool "MTD driver"
@@ -1159,9 +1164,12 @@ config ESPRESSIF_MTD
        select MTD
        select MTD_BYTE_WRITE
        select MTD_PARTITION
+       depends on !ESP32_PARTITION_TABLE && !ESP32S3_PARTITION_TABLE && 
!ESP32S3_SPIRAM
        ---help---
                Initialize an MTD driver for the ESP32-S2 SPI Flash, which will
                add an entry at /dev for application access from userspace.
+               When using partition table on SPIRAM, legacy drivers for SPI 
Flash
+               used instead, making this option not available.
 
 config ESPRESSIF_SPIFLASH_MTD_BLKSIZE
        int "Storage MTD block size"
@@ -1176,6 +1184,25 @@ config ESPRESSIF_STORAGE_MTD_DEBUG
                If this option is enabled, Storage MTD driver read and write 
functions
                will output input parameters and return values (if applicable).
 
+if ARCH_CHIP_ESP32S2
+
+config ESPRESSIF_STORAGE_MTD_OFFSET
+       hex "Storage MTD base address in SPI Flash"
+       default 0x180000 if !ESPRESSIF_BOOTLOADER_MCUBOOT
+       default 0x260000 if ESPRESSIF_BOOTLOADER_MCUBOOT
+       depends on ESPRESSIF_MTD
+       ---help---
+               MTD base address in SPI Flash.
+
+config ESPRESSIF_STORAGE_MTD_SIZE
+       hex "Storage MTD size in SPI Flash"
+       default 0x100000
+       depends on ESPRESSIF_MTD
+       ---help---
+               MTD size in SPI Flash.
+
+endif # ARCH_CHIP_ESP32S2
+
 endif # ESPRESSIF_SPIFLASH
 
 endmenu # SPI Flash Configuration
diff --git a/arch/xtensa/src/common/espressif/Make.defs 
b/arch/xtensa/src/common/espressif/Make.defs
index 93c71e918b3..0a506511212 100644
--- a/arch/xtensa/src/common/espressif/Make.defs
+++ b/arch/xtensa/src/common/espressif/Make.defs
@@ -119,6 +119,7 @@ endif
 
 CHIP_CSRCS += esp_efuse.c
 
+LDFLAGS += -u esp_system_include_startup_funcs
 ifeq ($(CONFIG_ESPRESSIF_EFUSE),y)
 LDFLAGS    += -u esp_efuse_startup_include_func
 endif
diff --git a/arch/xtensa/src/common/espressif/esp_spiflash.c 
b/arch/xtensa/src/common/espressif/esp_spiflash.c
index b0cace16fe6..ab82c8fd0dc 100644
--- a/arch/xtensa/src/common/espressif/esp_spiflash.c
+++ b/arch/xtensa/src/common/espressif/esp_spiflash.c
@@ -25,592 +25,311 @@
  ****************************************************************************/
 
 #include <nuttx/config.h>
+#include <nuttx/arch.h>
+#include <nuttx/init.h>
 
 #include <stdint.h>
 #include <assert.h>
 #include <debug.h>
-#include <string.h>
+#include <nuttx/mutex.h>
 #include <sys/types.h>
 #include <inttypes.h>
-#include <errno.h>
+#include <sched/sched.h>
 
-#include <nuttx/arch.h>
-#include <nuttx/init.h>
-#include "esp_spiflash.h"
-#include "esp_attr.h"
-#include "memspi_host_driver.h"
-#include "spi_flash_defs.h"
-#include "hal/spimem_flash_ll.h"
-#include "hal/spi_flash_ll.h"
-#include "esp_rom_spiflash.h"
-#include "esp32s2_irq.h"
-#ifndef CONFIG_ARCH_CHIP_ESP32S3
-#include "esp_private/spi_flash_os.h"
-#endif
+#include "esp_flash_internal.h"
+#include "esp_flash.h"
+#include "esp_flash_encrypt.h"
+#include "esp_private/cache_utils.h"
 
-#ifdef CONFIG_ARCH_CHIP_ESP32S3
-#define esp_intr_noniram_enable esp32s3_irq_noniram_disable
+#if defined(CONFIG_ARCH_CHIP_ESP32)
+#  include "esp32_irq.h"
+#elif defined(CONFIG_ARCH_CHIP_ESP32S2)
+#  include "esp32s2_irq.h"
+#else
+#  include "esp32s3_irq.h"
 #endif
 
 /****************************************************************************
  * Pre-processor Definitions
  ****************************************************************************/
 
-#ifndef CONFIG_ESPRESSIF_SPI_FLASH_USE_ROM_CODE
-/* SPI buffer size */
-
-#  define SPI_BUFFER_WORDS          (16)
-#  define SPI_BUFFER_BYTES          (SPI_BUFFER_WORDS * 4)
-
-/* SPI flash hardware definition */
-
-#  define FLASH_SECTOR_SIZE         (4096)
-
-/* SPI flash SR1 bits */
-
-#  define FLASH_SR1_BUSY            ESP_ROM_SPIFLASH_BUSY_FLAG
-#  define FLASH_SR1_WREN            ESP_ROM_SPIFLASH_WRENABLE_FLAG
+#if defined(CONFIG_ESP32_PARTITION_TABLE) || 
defined(CONFIG_ESP32S3_PARTITION_TABLE)
+#  error "Partition table requires legacy SPI Flash driver"
+#endif
 
-/* SPI flash operation */
+#if defined(CONFIG_ESP32S3_SPIRAM)
+#  error "SPIRAM requires legacy SPI Flash driver"
+#endif
 
-#  define FLASH_CMD_WRDI            CMD_WRDI
-#  define FLASH_CMD_WREN            CMD_WREN
-#  define FLASH_CMD_RDSR            CMD_RDSR
-#ifdef CONFIG_ESPRESSIF_SPI_FLASH_USE_32BIT_ADDRESS
-#  define ADDR_BITS(addr)         (((addr) & 0xff000000) ? 32 : 24)
-#  define READ_CMD(addr)          (ADDR_BITS(addr) == 32 ?                  \
-                                   CMD_FASTRD_4B : CMD_FASTRD)
-#  define WRITE_CMD(addr)         (ADDR_BITS(addr) == 32 ? CMD_PROGRAM_PAGE_4B 
: \
-                                   CMD_PROGRAM_PAGE)
-#  define ERASE_CMD(addr)         (ADDR_BITS(addr) == 32 ? CMD_SECTOR_ERASE_4B 
: \
-                                   CMD_SECTOR_ERASE)
-#  define READ_DUMMY(addr)        (8)
+#if defined(CONFIG_ARCH_CHIP_ESP32)
+#  define esp_intr_noniram_enable  esp32_irq_noniram_enable
+#  define esp_intr_noniram_disable esp32_irq_noniram_disable
+#elif defined(CONFIG_ARCH_CHIP_ESP32S2)
+#  define esp_intr_noniram_disable esp32s2_irq_noniram_disable
+#  define esp_intr_noniram_enable  esp32s2_irq_noniram_enable
 #else
-#  define ADDR_BITS(addr)         (24)
-#  define READ_CMD(addr)          CMD_FASTRD
-#  define WRITE_CMD(addr)         CMD_PROGRAM_PAGE
-#  define ERASE_CMD(addr)         CMD_SECTOR_ERASE
-#  define READ_DUMMY(addr)        (8)
+#  define esp_intr_noniram_enable  esp32s3_irq_noniram_enable
+#  define esp_intr_noniram_disable esp32s3_irq_noniram_disable
 #endif
 
-#  define SEND_CMD8_TO_FLASH(cmd)                           \
-    esp_spi_trans((cmd), 8,                                 \
-                  0, 0,                                     \
-                  NULL, 0,                                  \
-                  NULL, 0,                                  \
-                  0)
-
-#  define READ_SR1_FROM_FLASH(cmd, status)                  \
-    esp_spi_trans((cmd), 8,                                 \
-                  0, 0,                                     \
-                  NULL, 0,                                  \
-                  (status), 1,                              \
-                  0)
-
-#  define ERASE_FLASH_SECTOR(addr)                          \
-    esp_spi_trans(ERASE_CMD(addr), 8,                       \
-                  (addr), ADDR_BITS(addr),                  \
-                  NULL, 0,                                  \
-                  NULL, 0,                                  \
-                  0)
-
-#  define WRITE_DATA_TO_FLASH(addr, buffer, size)           \
-    esp_spi_trans(WRITE_CMD(addr), 8,                       \
-                  (addr), ADDR_BITS(addr),                  \
-                  buffer, size,                             \
-                  NULL, 0,                                  \
-                  0)
-
-#  define READ_DATA_FROM_FLASH(addr, buffer, size)          \
-    esp_spi_trans(READ_CMD(addr), 8,                        \
-                  (addr), ADDR_BITS(addr),                  \
-                  NULL, 0,                                  \
-                  buffer, size,                             \
-                  READ_DUMMY(addr))
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-spi_mem_dev_t *dev = spimem_flash_ll_get_hw(SPI1_HOST);
-#endif /* CONFIG_ESPRESSIF_SPI_FLASH_USE_ROM_CODE */
-
-/****************************************************************************
- * Private Functions Declaration
- ****************************************************************************/
-
-void spiflash_start(void);
-void spiflash_end(void);
-#if !CONFIG_ESPRESSIF_SPI_FLASH_USE_ROM_CODE && CONFIG_ARCH_CHIP_ESP32S3
-extern bool spi_flash_check_and_flush_cache(size_t start_addr,
-                                            size_t length);
-#endif /* CONFIG_ESPRESSIF_SPI_FLASH_USE_ROM_CODE */
+#define SPIFLASH_OP_TASK_STACKSIZE 768
 
 /****************************************************************************
  * Private Data
  ****************************************************************************/
 
-static struct spiflash_guard_funcs g_spi_flash_guard_funcs =
-{
-  .start           = spiflash_start,
-  .end             = spiflash_end,
-  .op_lock         = NULL,
-  .op_unlock       = NULL,
-  .address_is_safe = NULL,
-  .yield           = NULL,
-};
-
-static mutex_t s_flash_op_mutex;
-static uint32_t s_flash_op_cache_state[CONFIG_ESPRESSIF_NUM_CPUS];
-static volatile bool s_sched_suspended[CONFIG_ESPRESSIF_NUM_CPUS];
-
 /****************************************************************************
  * Private Functions
  ****************************************************************************/
 
 /****************************************************************************
- * Name: spiflash_start
- *
- * Description:
- *   Prepare for an SPIFLASH operation.
- *
- * Input Parameters:
- *   None.
- *
- * Returned Value:
- *   None.
- *
- ****************************************************************************/
-
-IRAM_ATTR void spiflash_start(void)
-{
-  extern uint32_t cache_suspend_icache(void);
-  int cpu;
-  irqstate_t flags;
-  uint32_t regval;
-
-  nxmutex_lock(&s_flash_op_mutex);
-  flags = enter_critical_section();
-  cpu = this_cpu();
-  s_sched_suspended[cpu] = true;
-
-#ifndef CONFIG_ARCH_CHIP_ESP32S2
-  esp_intr_noniram_disable();
-#endif
-
-  s_flash_op_cache_state[cpu] = cache_suspend_icache() << 16;
-
-  leave_critical_section(flags);
-}
-
-/****************************************************************************
- * Name: spiflash_end
+ * Name: spi_flash_op_block_task
  *
  * Description:
- *   Undo all the steps of opstart.
+ *   Disable the non-IRAM interrupts on the other core (the one that isn't
+ *   handling the SPI flash operation) and notify that the SPI flash
+ *   operation can start. Wait on a busy loop until it's finished and then
+ *   re-enable the non-IRAM interrupts.
  *
  * Input Parameters:
- *   None.
+ *   argc          - Not used.
+ *   argv          - Not used.
  *
  * Returned Value:
- *   None.
+ *   Zero (OK) is returned on success. A negated errno value is returned to
+ *   indicate the nature of any failure.
  *
  ****************************************************************************/
 
-IRAM_ATTR void spiflash_end(void)
+#ifdef CONFIG_SMP
+static int spi_flash_op_block_task(int argc, char *argv[])
 {
-  extern void cache_resume_icache(uint32_t);
-  extern void cache_invalidate_icache_all(void);
+  struct tcb_s *tcb = this_task();
+  int cpu = this_cpu();
 
-  int cpu;
-  irqstate_t flags;
+  for (; ; )
+    {
+      DEBUGASSERT((1 << cpu) & tcb->affinity);
+      /* Wait for a request from the other CPU to suspend interrupts
+       * and cache on this CPU.
+       */
 
-  flags = enter_critical_section();
+      nxsem_wait(&g_cpu_prepare_sem[cpu]);
 
-  cpu = this_cpu();
+      sched_lock();
+      esp_intr_noniram_disable();
 
-  cache_invalidate_icache_all();
-  cache_resume_icache(s_flash_op_cache_state[cpu] >> 16);
+      s_flash_op_complete = false;
+      s_flash_op_can_start = true;
+      while (!s_flash_op_complete)
+        {
+          /* Wait for a request to restore interrupts and cache on this CPU.
+           * This indicates SPI Flash operation is complete.
+           */
+        }
 
-#ifndef CONFIG_ARCH_CHIP_ESP32S2
-  esp_intr_noniram_enable();
-#endif
-  s_sched_suspended[cpu] = false;
+      esp_intr_noniram_enable();
+      sched_unlock();
+    }
 
-  leave_critical_section(flags);
-  nxmutex_unlock(&s_flash_op_mutex);
+  return OK;
 }
 
 /****************************************************************************
- * Name: esp_spi_trans
+ * Name: spiflash_init_spi_flash_op_block_task
  *
  * Description:
- *   Transmit given command, address and data.
+ *   Starts a kernel thread that waits for a semaphore indicating that a SPI
+ *   flash operation is going to take place in the other CPU.
  *
  * Input Parameters:
- *   command      - command value
- *   command_bits - command bits
- *   address      - address value
- *   address_bits - address bits
- *   tx_buffer    - write buffer
- *   tx_bytes     - write buffer size
- *   rx_buffer    - read buffer
- *   rx_bytes     - read buffer size
- *   dummy_bits   - dummy bits
+ *   cpu - The CPU core that will run the created task to wait on a busy
+ *         loop while the SPI flash operation finishes
  *
  * Returned Value:
- *   0 if success or a negative value if fail.
+ *   0 (OK) on success; A negated errno value on failure.
  *
  ****************************************************************************/
 
-#ifndef CONFIG_ESPRESSIF_SPI_FLASH_USE_ROM_CODE
-static IRAM_ATTR void esp_spi_trans(uint32_t command,
-                                    uint32_t command_bits,
-                                    uint32_t address,
-                                    uint32_t address_bits,
-                                    uint32_t *tx_buffer,
-                                    uint32_t tx_bytes,
-                                    uint32_t *rx_buffer,
-                                    uint32_t rx_bytes,
-                                    uint32_t dummy_bits)
+static int spiflash_init_spi_flash_op_block_task(int cpu)
 {
-  /* Initialize SPI user register */
-
-  spi_flash_ll_reset(dev);
+  FAR struct tcb_s *tcb;
+  int ret;
+  char *argv[2];
+  char arg1[32];
+  cpu_set_t cpuset;
 
-  while (!spi_flash_ll_host_idle(dev));
-
-  /* Set command bits and value, and command is always needed */
-
-  spi_flash_ll_set_command(dev, command, command_bits);
-
-  /* Set address bits and value */
-
-  if (address_bits)
-    {
-      spi_flash_ll_set_addr_bitlen(dev, address_bits);
-      spi_flash_ll_set_address(dev, address);
-    }
+  snprintf(arg1, sizeof(arg1), "%p", &cpu);
+  argv[0] = arg1;
+  argv[1] = NULL;
 
-  /* Set dummy */
+  /* Allocate a TCB for the new task. */
 
-  if (dummy_bits)
+  tcb = kmm_zalloc(sizeof(struct tcb_s));
+  if (!tcb)
     {
-      spi_flash_ll_set_dummy(dev, dummy_bits);
+      serr("ERROR: Failed to allocate TCB\n");
+      return -ENOMEM;
     }
 
-  /* Set TX data */
+  /* Setup the task type */
 
-  if (tx_bytes)
-    {
-      spi_flash_ll_set_mosi_bitlen(dev, tx_bytes * 8);
-      spi_flash_ll_set_buffer_data(dev, tx_buffer, tx_bytes);
-    }
+  tcb->flags = TCB_FLAG_TTYPE_KERNEL | TCB_FLAG_FREE_TCB;
 
-  /* Set RX data */
+  /* Initialize the task */
 
-  if (rx_bytes)
+  ret = nxtask_init((FAR struct task_tcb_s *)tcb, "spiflash_op",
+                    SCHED_PRIORITY_MAX,
+                    NULL, SPIFLASH_OP_TASK_STACKSIZE,
+                    spi_flash_op_block_task, argv, environ, NULL);
+  if (ret < OK)
     {
-      spi_flash_ll_set_miso_bitlen(dev, rx_bytes * 8);
+      kmm_free(tcb);
+      return ret;
     }
 
-  /* Set I/O mode */
-
-  spi_flash_ll_set_read_mode(dev, SPI_FLASH_FASTRD);
-
-  /* Set clock and delay */
-
-  spimem_flash_ll_suspend_cmd_setup(dev, 0);
-
-  /* Start transmission */
+  /* Set the affinity */
 
-  spi_flash_ll_user_start(dev, false);
-
-  /* Wait until transmission is done */
-
-  while (!spi_flash_ll_cmd_is_done(dev));
-
-  /* Get read data */
-
-  if (rx_bytes)
-    {
-      spi_flash_ll_get_buffer_data(dev, rx_buffer, rx_bytes);
-    }
-}
-
-/****************************************************************************
- * Name: wait_flash_idle
- *
- * Description:
- *   Wait until flash enters idle state
- *
- * Input Parameters:
- *   None.
- *
- * Returned Value:
- *   None.
- *
- ****************************************************************************/
-
-static IRAM_ATTR void wait_flash_idle(void)
-{
-  uint32_t status;
-
-  do
-    {
-      READ_SR1_FROM_FLASH(FLASH_CMD_RDSR, &status);
-      if ((status & FLASH_SR1_BUSY) == 0)
-        {
-          break;
-        }
-    }
-  while (1);
-}
-
-/****************************************************************************
- * Name: enable_flash_write
- *
- * Description:
- *   Enable Flash write mode
- *
- * Input Parameters:
- *   None.
- *
- * Returned Value:
- *   None.
- *
- ****************************************************************************/
+  CPU_ZERO(&cpuset);
+  CPU_SET(cpu, &cpuset);
+  tcb->affinity = cpuset;
 
-static IRAM_ATTR void enable_flash_write(void)
-{
-  uint32_t status;
+  /* Activate the task */
 
-  do
-    {
-      SEND_CMD8_TO_FLASH(FLASH_CMD_WREN);
-      READ_SR1_FROM_FLASH(FLASH_CMD_RDSR, &status);
+  nxtask_activate(tcb);
 
-      if ((status & FLASH_SR1_WREN) != 0)
-        {
-          break;
-        }
-    }
-  while (1);
+  return ret;
 }
+#endif
 
 /****************************************************************************
- * Name: disable_flash_write
- *
- * Description:
- *   Disable Flash write mode
- *
- * Input Parameters:
- *   None.
- *
- * Returned Value:
- *   None.
- *
+ * Public Functions
  ****************************************************************************/
 
-static IRAM_ATTR void disable_flash_write(void)
-{
-  uint32_t status;
-
-  do
-    {
-      SEND_CMD8_TO_FLASH(FLASH_CMD_WRDI);
-      READ_SR1_FROM_FLASH(FLASH_CMD_RDSR, &status);
-
-      if ((status & FLASH_SR1_WREN) == 0)
-        {
-          break;
-        }
-    }
-  while (1);
-}
-
 /****************************************************************************
- * Name: spi_flash_read
+ * Name: esp_spiflash_read
  *
  * Description:
- *   Read data from Flash.
+ *   Read data from flash.
  *
  * Parameters:
- *   address - source address of the data in Flash.
- *   buffer  - pointer to the destination buffer
- *   length  - length of data
+ *   address - Source address of the data in flash.
+ *   buffer  - Pointer to the destination buffer.
+ *   length  - Length of data in bytes.
  *
  * Returned Values:
  *   Zero (OK) is returned or a negative error.
  *
  ****************************************************************************/
 
-IRAM_ATTR int spi_flash_read(uint32_t address, void *buffer, uint32_t length)
+int esp_spiflash_read(uint32_t address, void *buffer,
+                      uint32_t length)
 {
   int ret = OK;
-  uint8_t *rx_buf = (uint8_t *)buffer;
-  uint32_t rx_bytes = length;
-  uint32_t rx_addr = address;
-
-  spiflash_start();
 
-  for (uint32_t i = 0; i < length; i += SPI_BUFFER_BYTES)
+  if (!esp_flash_encryption_enabled())
     {
-      uint32_t spi_buffer[SPI_BUFFER_WORDS];
-      uint32_t n = MIN(rx_bytes, SPI_BUFFER_BYTES);
-
-      READ_DATA_FROM_FLASH(rx_addr, spi_buffer, n);
-
-      memcpy(rx_buf, spi_buffer, n);
-      rx_bytes -= n;
-      rx_buf += n;
-      rx_addr += n;
+      ret = esp_flash_read(NULL, buffer, address, length);
+    }
+  else
+    {
+#ifdef CONFIG_ARCH_CHIP_ESP32S2
+      ferr("encryption not supported on ESP32-S2\n");
+      ret = ERROR;
+#else
+      ret = esp_flash_read_encrypted(NULL, address, buffer, length);
+#endif
     }
 
-  spiflash_end();
-
-  return ret;
-}
-
-/****************************************************************************
- * Name: spi_flash_erase_sector
- *
- * Description:
- *   Erase the Flash sector.
- *
- * Parameters:
- *   sector - Sector number, the count starts at sector 0, 4KB per sector.
- *
- * Returned Values: esp_err_t
- *   Zero (OK) is returned or a negative error.
- *
- ****************************************************************************/
-
-IRAM_ATTR int spi_flash_erase_sector(uint32_t sector)
-{
-  int ret = OK;
-  uint32_t addr = sector * FLASH_SECTOR_SIZE;
-
-  spiflash_start();
-
-  wait_flash_idle();
-  enable_flash_write();
-
-  ERASE_FLASH_SECTOR(addr);
-
-  wait_flash_idle();
-  disable_flash_write();
-
-  spiflash_end();
+  if (ret != 0)
+    {
+      ferr("esp_flash_read failed %d", ret);
+      ret = ERROR;
+    }
 
   return ret;
 }
 
 /****************************************************************************
- * Name: spi_flash_erase_range
+ * Name: esp_spiflash_write
  *
  * Description:
- *   Erase a range of flash sectors
+ *   Write data to Flash.
  *
  * Parameters:
- *   start_address - Address where erase operation has to start.
- *                   Must be 4kB-aligned
- *   size          - Size of erased range, in bytes. Must be divisible by
- *                   4kB.
+ *   address - Destination address in Flash.
+ *   buffer  - Pointer to the source buffer.
+ *   length  - Length of data, in bytes.
  *
  * Returned Values:
  *   Zero (OK) is returned or a negative error.
  *
  ****************************************************************************/
 
-IRAM_ATTR int spi_flash_erase_range(uint32_t start_address, uint32_t size)
+int esp_spiflash_write(uint32_t address, const void *buffer,
+                       uint32_t length)
 {
   int ret = OK;
-  uint32_t addr = start_address;
 
-  spiflash_start();
-
-  for (uint32_t i = 0; i < size; i += FLASH_SECTOR_SIZE)
+  if (!esp_flash_encryption_enabled())
     {
-      wait_flash_idle();
-      enable_flash_write();
-
-      ERASE_FLASH_SECTOR(addr);
-      addr += FLASH_SECTOR_SIZE;
+      ret = esp_flash_write(NULL, buffer, address, length);
     }
-
-  wait_flash_idle();
-  disable_flash_write();
-#ifdef CONFIG_ARCH_CHIP_ESP32S3
-  spi_flash_check_and_flush_cache(start_address, size);
+  else
+    {
+#ifdef CONFIG_ARCH_CHIP_ESP32S2
+      ferr("encryption not supported on ESP32-S2\n");
+      ret = -ERROR;
+#else
+      ret = esp_flash_write_encrypted(NULL, address, buffer, length);
 #endif
+    }
 
-  spiflash_end();
+  if (ret != 0)
+    {
+      ferr("ERROR: esp_flash_write failed %d", ret);
+      ret = ERROR;
+    }
 
   return ret;
 }
 
 /****************************************************************************
- * Name: spi_flash_write
+ * Name: esp_spiflash_erase
  *
  * Description:
- *   Write data to Flash.
+ *   Erase data from Flash.
  *
  * Parameters:
- *   dest_addr - Destination address in Flash.
- *   buffer    - Pointer to the source buffer.
- *   size      - Length of data, in bytes.
+ *   address - Start address of the data in Flash.
+ *   length  - Length of the data to erase.
  *
  * Returned Values:
  *   Zero (OK) is returned or a negative error.
  *
  ****************************************************************************/
 
-IRAM_ATTR int spi_flash_write(uint32_t dest_addr,
-                              const void *buffer,
-                              uint32_t size)
+int esp_spiflash_erase(uint32_t address, uint32_t length)
 {
   int ret = OK;
-  const uint8_t *tx_buf = (const uint8_t *)buffer;
-  uint32_t tx_bytes = size;
-  uint32_t tx_addr = dest_addr;
 
-  spiflash_start();
-
-  for (int i = 0; i < size; i += SPI_BUFFER_BYTES)
+  ret = esp_flash_erase_region(NULL, address, length);
+  if (ret != 0)
     {
-      uint32_t spi_buffer[SPI_BUFFER_WORDS];
-      uint32_t n = MIN(tx_bytes, SPI_BUFFER_BYTES);
-
-      memcpy(spi_buffer, tx_buf, n);
-
-      wait_flash_idle();
-      enable_flash_write();
-
-      WRITE_DATA_TO_FLASH(tx_addr, spi_buffer, n);
-
-      tx_bytes -= n;
-      tx_buf += n;
-      tx_addr += n;
+      ferr("ERROR: erase failed: ret=%d", ret);
+      ret = ERROR;
     }
 
-  wait_flash_idle();
-  disable_flash_write();
-#ifdef CONFIG_ARCH_CHIP_ESP32S3
-  spi_flash_check_and_flush_cache(start_address, size);
-#endif
-
-  spiflash_end();
-
   return ret;
 }
-#endif /* CONFIG_ESPRESSIF_SPI_FLASH_USE_ROM_CODE */
 
 /****************************************************************************
  * Name: esp_spiflash_init
  *
  * Description:
  *   Initialize ESP SPI flash driver.
+ *   SPI Flash actual chip initialization initial is done by esp_start on
+ *   STARTUP_FN hook.
  *
  * Input Parameters:
  *   None.
@@ -622,13 +341,25 @@ IRAM_ATTR int spi_flash_write(uint32_t dest_addr,
 
 int esp_spiflash_init(void)
 {
-#ifdef CONFIG_ARCH_CHIP_ESP32S3
-  extern void spi_flash_guard_set(const struct spiflash_guard_funcs *);
-#endif
+  int ret = OK;
+  int cpu;
 
-  nxmutex_init(&s_flash_op_mutex);
+#ifdef CONFIG_SMP
+  sched_lock();
 
-  spi_flash_guard_set((spi_flash_guard_funcs_t *)&g_spi_flash_guard_funcs);
+  for (cpu = 0; cpu < CONFIG_SMP_NCPUS; cpu++)
+    {
+      ret = spiflash_init_spi_flash_op_block_task(cpu);
+      if (ret != OK)
+        {
+          return ret;
+        }
+    }
 
-  return OK;
+  sched_unlock();
+#else
+  UNUSED(cpu);
+#endif
+
+  return ret;
 }
diff --git a/arch/xtensa/src/common/espressif/esp_spiflash.h 
b/arch/xtensa/src/common/espressif/esp_spiflash.h
index 8c7f64c81b8..d4f95f9f2d8 100644
--- a/arch/xtensa/src/common/espressif/esp_spiflash.h
+++ b/arch/xtensa/src/common/espressif/esp_spiflash.h
@@ -48,122 +48,63 @@ extern "C"
  * Public Types
  ****************************************************************************/
 
-/**
- * Structure holding SPI flash access critical sections management functions.
- *
- * Flash API uses two types of functions for flash access management:
- * 1) Functions which prepare/restore flash cache and interrupts before
- *    calling appropriate ROM functions (spi_flash_write, spi_flash_read,
- *    spi_flash_erase_sector and spi_flash_erase_range):
- *   - 'start' function should disable flash cache and non-IRAM interrupts
- *      and is invoked before the call to one of ROM functions from
- *      "struct spiflash_guard_funcs".
- *   - 'end' function should restore state of flash cache and non-IRAM
- *      interrupts and is invoked after the call to one of ROM
- *      functions from "struct spiflash_guard_funcs".
- *    These two functions are not reentrant.
- * 2) Functions which synchronizes access to internal data used by flash API.
- *    These functions are mostly intended to synchronize access to flash API
- *    internal data in multithreaded environment and use OS primitives:
- *   - 'op_lock' locks access to flash API internal data.
- *   - 'op_unlock' unlocks access to flash API internal data.
- *   These two functions are reentrant and can be used around the outside of
- *   multiple calls to 'start' & 'end', in order to create atomic multi-part
- *   flash operations.
- *
- * Structure and corresponding guard functions should not reside
- * in flash. For example structure can be placed in DRAM and functions
- * in IRAM sections.
- */
-
-struct spiflash_guard_funcs
-{
-  void (*start)(void);      /* critical section start function */
-  void (*end)(void);        /* critical section end function */
-  void (*op_lock)(void);    /* flash access API lock function */
-  void (*op_unlock)(void);  /* flash access API unlock function */
-
-  /* checks flash write addresses */
-
-  bool (*address_is_safe)(size_t addr, size_t size);
-
-  void (*yield)(void);      /* yield to the OS during flash erase */
-};
-
 /****************************************************************************
  * Public Function Prototypes
  ****************************************************************************/
 
 /****************************************************************************
- * Name: spi_flash_read
+ * Name: esp_spiflash_read
  *
  * Description:
  *   Read data from Flash.
  *
  * Parameters:
- *   address - source address of the data in Flash.
- *   buffer  - pointer to the destination buffer
- *   length  - length of data
+ *   address - Source address of the data in Flash.
+ *   buffer  - Pointer to the destination buffer.
+ *   length  - Length of data in bytes.
  *
  * Returned Values:
  *   Zero (OK) is returned or a negative error.
  *
  ****************************************************************************/
 
-int spi_flash_read(uint32_t address, void *buffer, uint32_t length);
-
-/****************************************************************************
- * Name: spi_flash_erase_sector
- *
- * Description:
- *   Erase the Flash sector.
- *
- * Parameters:
- *   sector - Sector number, the count starts at sector 0, 4KB per sector.
- *
- * Returned Values: esp_err_t
- *   Zero (OK) is returned or a negative error.
- *
- ****************************************************************************/
-
-int spi_flash_erase_sector(uint32_t sector);
+int esp_spiflash_read(uint32_t address, void *buffer, uint32_t length);
 
 /****************************************************************************
- * Name: spi_flash_erase_range
+ * Name: esp_spiflash_erase
  *
  * Description:
- *   Erase a range of flash sectors
+ *   Erase data from Flash.
  *
  * Parameters:
- *   start_address - Address where erase operation has to start.
- *                   Must be 4kB-aligned
- *   size          - Size of erased range, in bytes. Must be divisible by
- *                   4kB.
+ *   address - Start address of the data in Flash.
+ *   length  - Length of the data to erase.
  *
  * Returned Values:
  *   Zero (OK) is returned or a negative error.
  *
  ****************************************************************************/
 
-int spi_flash_erase_range(uint32_t start_address, uint32_t size);
+int esp_spiflash_erase(uint32_t address, uint32_t length);
 
 /****************************************************************************
- * Name: spi_flash_write
+ * Name: esp_spiflash_write
  *
  * Description:
  *   Write data to Flash.
  *
  * Parameters:
- *   dest_addr - Destination address in Flash.
- *   src       - Pointer to the source buffer.
- *   size      - Length of data, in bytes.
+ *   address - Destination address in Flash.
+ *   buffer  - Pointer to the source buffer.
+ *   length  - Length of data, in bytes.
  *
  * Returned Values:
  *   Zero (OK) is returned or a negative error.
  *
  ****************************************************************************/
 
-int spi_flash_write(uint32_t dest_addr, const void *buffer, uint32_t size);
+int esp_spiflash_write(uint32_t address, const void *buffer,
+                       uint32_t length);
 
 /****************************************************************************
  * Name: esp_spiflash_init
diff --git a/arch/xtensa/src/common/espressif/esp_spiflash_mtd.c 
b/arch/xtensa/src/common/espressif/esp_spiflash_mtd.c
index 9d5af8df187..bce92b825f8 100644
--- a/arch/xtensa/src/common/espressif/esp_spiflash_mtd.c
+++ b/arch/xtensa/src/common/espressif/esp_spiflash_mtd.c
@@ -54,8 +54,6 @@
 #define MTD_ERASE_SIZE              4096
 #define MTD_ERASED_STATE            (0xff)
 
-#define MTD2PRIV(_dev)              ((struct esp_mtd_dev_s *)_dev)
-#define MTD_BLK2SIZE(_priv, _b)     (MTD_BLK_SIZE * (_b))
 #define MTD_SIZE2BLK(_priv, _s)     ((_s) / MTD_BLK_SIZE)
 #if defined(CONFIG_ARCH_CHIP_ESP32) || defined(CONFIG_ARCH_CHIP_ESP32S2)
 #define MTD_SIZE(_priv)             (((_priv)->data)->chip_size)
@@ -160,32 +158,16 @@ static int esp_erase(struct mtd_dev_s *dev, off_t 
startblock,
       return -EINVAL;
     }
 
-#ifdef CONFIG_ESPRESSIF_STORAGE_MTD_DEBUG
-  finfo("%s(%p, 0x%x, %d)\n", __func__, dev, startblock, nblocks);
-
-  finfo("spi_flash_erase_range(0x%x, %d)\n", offset, nbytes);
-#endif
-
-  flags = enter_critical_section();
-  ret = spi_flash_erase_range(offset, nbytes);
-  leave_critical_section(flags);
-
+  ret = esp_spiflash_erase(offset, nbytes);
   if (ret == OK)
     {
       ret = nblocks;
     }
   else
     {
-#ifdef CONFIG_ESPRESSIF_STORAGE_MTD_DEBUG
-      finfo("Failed to erase the flash range!\n");
-#endif
-      ret = -1;
+      ret = ERROR;
     }
 
-#ifdef CONFIG_ESPRESSIF_STORAGE_MTD_DEBUG
-  finfo("%s()=%d\n", __func__, ret);
-#endif
-
   return ret;
 }
 
@@ -210,27 +192,13 @@ static ssize_t esp_read(struct mtd_dev_s *dev, off_t 
offset,
                         size_t nbytes, uint8_t *buffer)
 {
   ssize_t ret;
-  irqstate_t flags;
-
-#ifdef CONFIG_ESPRESSIF_STORAGE_MTD_DEBUG
-  finfo("%s(%p, 0x%x, %d, %p)\n", __func__, dev, offset, nbytes, buffer);
-
-  finfo("spi_flash_read(0x%x, %p, %d)\n", offset, buffer, nbytes);
-#endif
-
-  flags = enter_critical_section();
-  ret = spi_flash_read(offset, (uint32_t *)buffer, nbytes);
-  leave_critical_section(flags);
 
+  ret = esp_spiflash_read(offset, (uint32_t *)buffer, nbytes);
   if (ret == OK)
     {
       ret = nbytes;
     }
 
-#ifdef CONFIG_ESPRESSIF_STORAGE_MTD_DEBUG
-  finfo("%s()=%d\n", __func__, ret);
-#endif
-
   return ret;
 }
 
@@ -257,28 +225,13 @@ static ssize_t esp_bread(struct mtd_dev_s *dev, off_t 
startblock,
   ssize_t ret;
   uint32_t addr = startblock * MTD_BLK_SIZE;
   uint32_t size = nblocks * MTD_BLK_SIZE;
-  irqstate_t flags;
-
-#ifdef CONFIG_ESPRESSIF_STORAGE_MTD_DEBUG
-  finfo("%s(%p, 0x%x, %d, %p)\n", __func__, dev, startblock, nblocks,
-        buffer);
-
-  finfo("spi_flash_read(0x%x, %p, %d)\n", addr, buffer, size);
-#endif
-
-  flags = enter_critical_section();
-  ret = spi_flash_read(addr, (uint32_t *)buffer, size);
-  leave_critical_section(flags);
 
+  ret = esp_spiflash_read(addr, (uint32_t *)buffer, size);
   if (ret == OK)
     {
       ret = nblocks;
     }
 
-#ifdef CONFIG_ESPRESSIF_STORAGE_MTD_DEBUG
-  finfo("%s()=%d\n", __func__, ret);
-#endif
-
   return ret;
 }
 
@@ -304,7 +257,6 @@ static ssize_t esp_write(struct mtd_dev_s *dev, off_t 
offset,
 {
   ssize_t ret;
   struct esp_mtd_dev_s *priv = (struct esp_mtd_dev_s *)dev;
-  irqstate_t flags;
 
   ASSERT(buffer);
 
@@ -313,25 +265,12 @@ static ssize_t esp_write(struct mtd_dev_s *dev, off_t 
offset,
       return -EINVAL;
     }
 
-#ifdef CONFIG_ESPRESSIF_STORAGE_MTD_DEBUG
-  finfo("%s(%p, 0x%x, %d, %p)\n", __func__, dev, offset, nbytes, buffer);
-
-  finfo("spi_flash_write(0x%x, %p, %d)\n", offset, buffer, nbytes);
-#endif
-
-  flags = enter_critical_section();
-  ret = spi_flash_write(offset, (uint32_t *)buffer, nbytes);
-  leave_critical_section(flags);
-
+  ret = esp_spiflash_write(offset, (uint32_t *)buffer, nbytes);
   if (ret == OK)
     {
       ret = nbytes;
     }
 
-#ifdef CONFIG_ESPRESSIF_STORAGE_MTD_DEBUG
-  finfo("%s()=%d\n", __func__, ret);
-#endif
-
   return ret;
 }
 
@@ -359,28 +298,13 @@ static ssize_t esp_bwrite(struct mtd_dev_s *dev, off_t 
startblock,
   ssize_t ret;
   uint32_t addr = startblock * MTD_BLK_SIZE;
   uint32_t size = nblocks * MTD_BLK_SIZE;
-  irqstate_t flags;
-
-#ifdef CONFIG_ESPRESSIF_STORAGE_MTD_DEBUG
-  finfo("%s(%p, 0x%x, %d, %p)\n", __func__, dev, startblock,
-        nblocks, buffer);
-
-  finfo("spi_flash_write(0x%x, %p, %d)\n", addr, buffer, size);
-#endif
-
-  flags = enter_critical_section();
-  ret = spi_flash_write(addr, (uint32_t *)buffer, size);
-  leave_critical_section(flags);
 
+  ret = esp_spiflash_write(addr, (uint32_t *)buffer, size);
   if (ret == OK)
     {
       ret = nblocks;
     }
 
-#ifdef CONFIG_ESPRESSIF_STORAGE_MTD_DEBUG
-  finfo("%s()=%d\n", __func__, ret);
-#endif
-
   return ret;
 }
 
diff --git a/arch/xtensa/src/esp32/Kconfig b/arch/xtensa/src/esp32/Kconfig
index a77fb9d4ff2..369bcd7eafa 100644
--- a/arch/xtensa/src/esp32/Kconfig
+++ b/arch/xtensa/src/esp32/Kconfig
@@ -597,6 +597,7 @@ config ESP32_SPIFLASH
        select MTD
        select MTD_BYTE_WRITE
        select MTD_PARTITION
+       select ESPRESSIF_SPIFLASH
 
 config ESP32_SPI2
        bool "SPI 2"
diff --git a/arch/xtensa/src/esp32/Make.defs b/arch/xtensa/src/esp32/Make.defs
index 8e2620eaa9a..7c4c764451b 100644
--- a/arch/xtensa/src/esp32/Make.defs
+++ b/arch/xtensa/src/esp32/Make.defs
@@ -96,18 +96,6 @@ CHIP_CSRCS += esp32_spi_slave.c
 endif
 endif
 
-# SPIFLASH and SPIRAM need spicache.c
-
-ifeq ($(CONFIG_ESP32_SPIFLASH),y)
-CHIP_CSRCS += esp32_spicache.c
-else ifeq ($(CONFIG_ESP32_SPIRAM),y)
-CHIP_CSRCS += esp32_spicache.c
-endif
-
-ifeq ($(CONFIG_ESP32_SPIFLASH),y)
-CHIP_CSRCS += esp32_spiflash.c
-endif
-
 ifeq ($(CONFIG_ESP32_SPIRAM),y)
 CHIP_CSRCS += esp32_spiram.c
 CHIP_CSRCS += esp32_psram.c
@@ -152,6 +140,7 @@ CHIP_CSRCS += esp32_freerun.c
 endif
 
 ifeq ($(CONFIG_ESP32_PARTITION_TABLE),y)
+CHIP_CSRCS += esp32_spiflash.c
 CHIP_CSRCS += esp32_partition.c
 endif
 
@@ -223,7 +212,7 @@ endif
 
 ESP_HAL_3RDPARTY_REPO   = esp-hal-3rdparty
 ifndef ESP_HAL_3RDPARTY_VERSION
-       ESP_HAL_3RDPARTY_VERSION = b6fa6c9098318007a61acc7c9f0f180443bb80c2
+       ESP_HAL_3RDPARTY_VERSION = 4eed03a15b2678a81dfd1ed0f3bde042b1fdd4c4
 endif
 
 ifndef ESP_HAL_3RDPARTY_URL
diff --git a/arch/xtensa/src/esp32/esp32_ble_adapter.c 
b/arch/xtensa/src/esp32/esp32_ble_adapter.c
index 325b0e77b85..a2980b03ada 100644
--- a/arch/xtensa/src/esp32/esp32_ble_adapter.c
+++ b/arch/xtensa/src/esp32/esp32_ble_adapter.c
@@ -58,13 +58,13 @@
 #include "espressif/esp_wireless.h"
 #include "espressif/esp_wifi_utils.h"
 #include "esp32_irq.h"
-#include "esp32_spicache.h"
 
 #include "esp_bt.h"
 #include "esp_log.h"
 #include "esp_mac.h"
 #include "esp_private/phy.h"
 #include "esp_private/wifi.h"
+#include "esp_private/cache_utils.h"
 #include "esp_random.h"
 #include "esp_timer.h"
 #include "periph_ctrl.h"
@@ -123,7 +123,7 @@
 
 #define MSG_QUEUE_NAME_SIZE                 16
 
-#ifdef CONFIG_ESP32_SPIFLASH
+#ifdef CONFIG_ESPRESSIF_SPIFLASH
 #  define BLE_TASK_EVENT_QUEUE_ITEM_SIZE    8
 #  define BLE_TASK_EVENT_QUEUE_LEN          8
 #endif
@@ -278,7 +278,7 @@ typedef enum
 struct bt_sem_s
 {
   sem_t sem;
-#ifdef CONFIG_ESP32_SPIFLASH
+#ifdef CONFIG_ESPRESSIF_SPIFLASH
   struct esp_semcache_s sc;
 #endif
 };
@@ -691,7 +691,7 @@ static struct irqstate_list_s 
g_ble_int_flags[NR_IRQSTATE_FLAGS];
 
 /* Cached queue control variables */
 
-#ifdef CONFIG_ESP32_SPIFLASH
+#ifdef CONFIG_ESPRESSIF_SPIFLASH
 static struct esp_queuecache_s g_esp_queuecache[BLE_TASK_EVENT_QUEUE_LEN];
 static uint8_t g_esp_queuecache_buffer[BLE_TASK_EVENT_QUEUE_ITEM_SIZE];
 #endif
@@ -1011,7 +1011,7 @@ static void *semphr_create_wrapper(uint32_t max, uint32_t 
init)
       return NULL;
     }
 
-#ifdef CONFIG_ESP32_SPIFLASH
+#ifdef CONFIG_ESPRESSIF_SPIFLASH
   esp_init_semcache(&bt_sem->sc, &bt_sem->sem);
 #endif
 
@@ -1084,7 +1084,7 @@ static int32_t IRAM_ATTR 
semphr_give_from_isr_wrapper(void *semphr,
   int ret;
   struct bt_sem_s *bt_sem = (struct bt_sem_s *)semphr;
 
-#ifdef CONFIG_ESP32_SPIFLASH
+#ifdef CONFIG_ESPRESSIF_SPIFLASH
   if (spi_flash_cache_enabled())
     {
       ret = semphr_give_wrapper(bt_sem);
@@ -1326,7 +1326,7 @@ static void *queue_create_wrapper(uint32_t queue_len, 
uint32_t item_size)
 
   mq_adpt->msgsize = item_size;
 
-#ifdef CONFIG_ESP32_SPIFLASH
+#ifdef CONFIG_ESPRESSIF_SPIFLASH
   if (queue_len <= BLE_TASK_EVENT_QUEUE_LEN &&
       item_size == BLE_TASK_EVENT_QUEUE_ITEM_SIZE)
     {
@@ -2421,7 +2421,7 @@ static IRAM_ATTR int32_t esp_queue_send_generic(void 
*queue, void *item,
   struct timespec timeout;
   struct mq_adpt_s *mq_adpt = (struct mq_adpt_s *)queue;
 
-#ifdef CONFIG_ESP32_SPIFLASH
+#ifdef CONFIG_ESPRESSIF_SPIFLASH
   if (!spi_flash_cache_enabled())
     {
       esp_send_queuecache(queue, item, mq_adpt->msgsize);
@@ -2917,7 +2917,7 @@ int esp32_bt_controller_init(void)
       sq_addlast((sq_entry_t *)&g_ble_int_flags[i], &g_ble_int_flags_free);
     }
 
-#ifdef CONFIG_ESP32_SPIFLASH
+#ifdef CONFIG_ESPRESSIF_SPIFLASH
 
   /* Initialize interfaces that enable BLE ISRs to run during a
    * SPI flash operation.
diff --git a/arch/xtensa/src/esp32/esp32_spiram.c 
b/arch/xtensa/src/esp32/esp32_spiram.c
index fd0f0c376d2..297437b8b52 100644
--- a/arch/xtensa/src/esp32/esp32_spiram.c
+++ b/arch/xtensa/src/esp32/esp32_spiram.c
@@ -37,13 +37,14 @@
 #include <nuttx/nuttx.h>
 
 #include "esp32_spiram.h"
-#include "esp32_spicache.h"
 #include "esp32_psram.h"
 #include "xtensa.h"
 #include "xtensa_attr.h"
 #include "hardware/esp32_soc.h"
 #include "hardware/esp32_dport.h"
 
+#include "esp_private/cache_utils.h"
+
 /****************************************************************************
  * Pre-processor Definitions
  ****************************************************************************/
@@ -215,10 +216,10 @@ unsigned int IRAM_ATTR cache_sram_mmu_set(int cpu_no, int 
pid,
       while (!g_cpu_pause);
     }
 
-  spi_disable_cache(1);
+    spi_flash_disable_cache(1, 0);
 #endif
 
-  spi_disable_cache(0);
+  spi_flash_disable_cache(0, 0);
 
   /* mmu change */
 
@@ -244,9 +245,9 @@ unsigned int IRAM_ATTR cache_sram_mmu_set(int cpu_no, int 
pid,
       putreg32(regval, DPORT_APP_CACHE_CTRL1_REG);
     }
 
-  spi_enable_cache(0);
+  spi_flash_enable_cache(0);
 #ifdef CONFIG_SMP
-  spi_enable_cache(1);
+  spi_flash_enable_cache(1);
 
   if (os_ready)
     {
diff --git a/arch/xtensa/src/esp32/esp32_user.c 
b/arch/xtensa/src/esp32/esp32_user.c
index 4f70f7a4f80..6710300fca2 100644
--- a/arch/xtensa/src/esp32/esp32_user.c
+++ b/arch/xtensa/src/esp32/esp32_user.c
@@ -33,7 +33,7 @@
 #include <debug.h>
 
 #include "xtensa.h"
-#include "esp32_spicache.h"
+#include "esp_private/cache_utils.h"
 
 /****************************************************************************
  * Public Data
@@ -324,19 +324,19 @@ static void advance_pc(uint32_t *regs, int diff)
 
 uint32_t *xtensa_user(int exccause, uint32_t *regs)
 {
-#ifdef CONFIG_ESP32_SPIFLASH
+#ifdef CONFIG_ESPRESSIF_SPIFLASH
   bool is_cache_reenabled = false;
 
   if (!spi_flash_cache_enabled())
     {
       is_cache_reenabled = true;
 
-      spi_enable_cache(0);
+      spi_flash_restore_cache(0, 0);
 #  ifdef CONFIG_SMP
-      spi_enable_cache(1);
+      spi_flash_restore_cache(1, 0);
 #  endif
     }
-#endif /* CONFIG_ESP32_SPIFLASH */
+#endif /* CONFIG_ESPRESSIF_SPIFLASH */
 
 #ifdef CONFIG_ARCH_USE_TEXT_HEAP
   /* Emulate byte access for module text.
@@ -447,21 +447,21 @@ uint32_t *xtensa_user(int exccause, uint32_t *regs)
         }
 
 return_with_regs:
-#  ifdef CONFIG_ESP32_SPIFLASH
+#  ifdef CONFIG_ESPRESSIF_SPIFLASH
       if (is_cache_reenabled)
         {
-          spi_disable_cache(0);
+          spi_flash_disable_cache(0, 0);
 #    ifdef CONFIG_SMP
-          spi_disable_cache(1);
+          spi_flash_disable_cache(1, 0);
 #    endif
         }
-#  endif /* CONFIG_ESP32_SPIFLASH */
+#  endif /* CONFIG_ESPRESSIF_SPIFLASH */
 
       return regs;
     }
 
 #else
-#  ifdef CONFIG_ESP32_SPIFLASH
+#  ifdef CONFIG_ESPRESSIF_SPIFLASH
   UNUSED(is_cache_reenabled);
 #  endif
 #endif
diff --git a/arch/xtensa/src/esp32/hal.mk b/arch/xtensa/src/esp32/hal.mk
index c10a1f3df52..c6153b8c506 100644
--- a/arch/xtensa/src/esp32/hal.mk
+++ b/arch/xtensa/src/esp32/hal.mk
@@ -124,7 +124,11 @@ CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)port$(DELIM)esp_clk_tree_common.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)regi2c_ctrl.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)sleep_modes.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)power_supply$(DELIM)brownout.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_mm$(DELIM)esp_mmu_map.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_mm$(DELIM)port$(DELIM)$(CHIP_SERIES)$(DELIM)ext_mem_layout.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_mm$(DELIM)esp_cache.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_mm$(DELIM)cache_esp32.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_phy$(DELIM)$(CHIP_SERIES)$(DELIM)phy_init_data.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_phy$(DELIM)src$(DELIM)phy_common.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_phy$(DELIM)src$(DELIM)phy_init.c
@@ -132,6 +136,8 @@ CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_wdt.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_system$(DELIM)esp_err.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_system$(DELIM)startup.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_system$(DELIM)startup_funcs.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_system$(DELIM)system_time.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_system$(DELIM)port$(DELIM)cpu_start.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_system$(DELIM)port$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)clk.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_system$(DELIM)port$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)system_internal.c
@@ -156,7 +162,30 @@ CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)i2c_hal.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)sha_hal.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)hal_utils.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)spi_flash_hal.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)spi_flash_hal_iram.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)wdt_hal_iram.c
+
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)spi_flash_encrypt_hal_iram.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)$(CHIP_SERIES)$(DELIM)cache_hal_esp32.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)dport_access_common.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_wrap.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_os_func_noos.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_os_func_app.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_generic.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_gd.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_winbond.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_issi.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_mxic_opi.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_mxic.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)esp_flash_api.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)flash_ops.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_drivers.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)memspi_host_driver.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)esp_flash_spi_init.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)flash_mmap.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)flash_brownout_hook.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)cache_utils.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)log_level$(DELIM)log_level.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)log_level$(DELIM)tag_log_level$(DELIM)tag_log_level.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)log_level$(DELIM)tag_log_level$(DELIM)linked_list$(DELIM)log_linked_list.c
@@ -164,6 +193,7 @@ CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)noos$(DELIM)log_lock.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)noos$(DELIM)log_timestamp.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)os$(DELIM)log_write.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)os$(DELIM)util.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)mbedtls$(DELIM)port$(DELIM)sha$(DELIM)core$(DELIM)esp_sha256.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)adc_periph.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)gpio_periph.c
@@ -174,10 +204,13 @@ CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)i2c_periph.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)i2s_periph.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)mcpwm_periph.c
-CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_wrap.c
 
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)nuttx$(DELIM)src$(DELIM)components$(DELIM)esp_driver_gpio$(DELIM)src$(DELIM)rtc_io.c
 
+# Bootloader files
+
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)flash_encrypt.c
+
 ifeq ($(CONFIG_ESPRESSIF_SIMPLE_BOOT),y)
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)nuttx$(DELIM)src$(DELIM)bootloader_banner_wrap.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)bootloader_console.c
@@ -198,12 +231,10 @@ ifeq ($(CONFIG_ESPRESSIF_SIMPLE_BOOT),y)
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)esp_image_format.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)${CHIP_SERIES}$(DELIM)bootloader_soc.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)bootloader_sha.c
-  CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)flash_encrypt.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)port$(DELIM)$(CHIP_SERIES)$(DELIM)rtc_clk_init.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_sys.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_spiflash.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_crc.c
-  CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)wdt_hal_iram.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)mpu_hal.c
 
   LDFLAGS += --wrap=bootloader_print_banner
diff --git a/arch/xtensa/src/esp32s2/Make.defs 
b/arch/xtensa/src/esp32s2/Make.defs
index 10a6ab37a87..e9f0d693b4a 100644
--- a/arch/xtensa/src/esp32s2/Make.defs
+++ b/arch/xtensa/src/esp32s2/Make.defs
@@ -133,7 +133,7 @@ endif
 
 ESP_HAL_3RDPARTY_REPO   = esp-hal-3rdparty
 ifndef ESP_HAL_3RDPARTY_VERSION
-       ESP_HAL_3RDPARTY_VERSION = 6782de1b073f93a54c501edf23d99a42a23d41ac
+       ESP_HAL_3RDPARTY_VERSION = 4eed03a15b2678a81dfd1ed0f3bde042b1fdd4c4
 endif
 
 ifndef ESP_HAL_3RDPARTY_URL
diff --git a/arch/xtensa/src/esp32s2/hal.mk b/arch/xtensa/src/esp32s2/hal.mk
index ff561b8a4b3..43b92fd223a 100644
--- a/arch/xtensa/src/esp32s2/hal.mk
+++ b/arch/xtensa/src/esp32s2/hal.mk
@@ -120,9 +120,16 @@ CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_common$(DELIM)src$(DELIM)esp_err_to_name.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)mspi_timing_tuning$(DELIM)mspi_timing_tuning.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)sleep_modes.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)power_supply$(DELIM)brownout.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_mm$(DELIM)esp_mmu_map.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_mm$(DELIM)port$(DELIM)$(CHIP_SERIES)$(DELIM)ext_mem_layout.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_mm$(DELIM)esp_cache.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_phy$(DELIM)$(CHIP_SERIES)$(DELIM)phy_init_data.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)hal_utils.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)spi_flash_hal.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)spi_flash_hal_iram.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)spi_flash_hal_gpspi.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)spi_flash_encrypt_hal_iram.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)log_level$(DELIM)log_level.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)log_level$(DELIM)tag_log_level$(DELIM)tag_log_level.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)log_level$(DELIM)tag_log_level$(DELIM)linked_list$(DELIM)log_linked_list.c
@@ -130,6 +137,7 @@ CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)noos$(DELIM)log_lock.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)noos$(DELIM)log_timestamp.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)os$(DELIM)log_write.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)os$(DELIM)util.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)mbedtls$(DELIM)port$(DELIM)sha$(DELIM)core$(DELIM)esp_sha256.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)nuttx$(DELIM)src$(DELIM)components$(DELIM)esp_driver_gpio$(DELIM)src$(DELIM)rtc_io.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)adc_share_hw_ctrl.c
@@ -155,6 +163,8 @@ CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_wdt.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_system$(DELIM)esp_err.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_system$(DELIM)startup.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_system$(DELIM)startup_funcs.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_system$(DELIM)system_time.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_system$(DELIM)port$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)clk.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_system$(DELIM)port$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)system_internal.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)adc_hal_common.c
@@ -192,8 +202,24 @@ CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)i2c_periph.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)i2s_periph.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)temperature_sensor_periph.c
-CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)flash_ops.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_wrap.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_os_func_noos.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_os_func_app.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_generic.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_boya.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_gd.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_winbond.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_issi.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_mxic_opi.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_mxic.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_th.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)esp_flash_api.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)flash_ops.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_drivers.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)memspi_host_driver.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)esp_flash_spi_init.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)flash_mmap.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)flash_brownout_hook.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)cache_utils.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)ulp$(DELIM)ulp_common$(DELIM)ulp_common.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)ulp$(DELIM)ulp_common$(DELIM)ulp_adc.c
@@ -205,6 +231,7 @@ CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_
 # Bootloader files
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)${CHIP_SERIES}$(DELIM)bootloader_soc.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)bootloader_random_${CHIP_SERIES}.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)flash_encrypt.c
 
 ifeq ($(CONFIG_ESPRESSIF_SIMPLE_BOOT),y)
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)nuttx$(DELIM)src$(DELIM)bootloader_banner_wrap.c
@@ -224,7 +251,6 @@ ifeq ($(CONFIG_ESPRESSIF_SIMPLE_BOOT),y)
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)bootloader_random.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)esp_image_format.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)bootloader_sha.c
-  CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)flash_encrypt.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)${CHIP_SERIES}$(DELIM)uart_periph.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_uart.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_sys.c
diff --git a/arch/xtensa/src/esp32s3/Kconfig b/arch/xtensa/src/esp32s3/Kconfig
index 6ef43770df9..cbe941cc610 100644
--- a/arch/xtensa/src/esp32s3/Kconfig
+++ b/arch/xtensa/src/esp32s3/Kconfig
@@ -1823,6 +1823,7 @@ config ESP32S3_TICKLESS
 
 config ESP32S3_SPIFLASH
        bool "SPI Flash MTD Partition"
+       select ESPRESSIF_SPIFLASH if !ESP32S3_PARTITION_TABLE && !ESP32S3_SPIRAM
        default n
 
 menu "SPI Flash configuration"
@@ -1895,7 +1896,7 @@ endchoice # ESP32S3_FLASH_SAMPLE_MODE
 
 config ESP32S3_SPI_FLASH_DONT_USE_ROM_CODE
        bool "Don't use SPI flash driver in ROM"
-       default n
+       default y
        ---help---
                Use source code for SPI flash driver instead of functions
                in ROM.
@@ -1985,6 +1986,7 @@ config ESP32S3_MTD
        select MTD
        select MTD_BYTE_WRITE
        select MTD_PARTITION
+       select ESPRESSIF_MTD if !ESP32S3_PARTITION_TABLE && !ESP32S3_SPIRAM
        ---help---
                Initialize an MTD driver for the ESP32-S3 SPI Flash, which will
                add an entry at /dev for application access from userspace.
diff --git a/arch/xtensa/src/esp32s3/Make.defs 
b/arch/xtensa/src/esp32s3/Make.defs
index 7eb57f0f3e5..5744f182d63 100644
--- a/arch/xtensa/src/esp32s3/Make.defs
+++ b/arch/xtensa/src/esp32s3/Make.defs
@@ -113,15 +113,17 @@ ifeq ($(CONFIG_ESP32S3_SPI),y)
   endif
 endif
 
+# Partition table and SPIRAM requires legacy spiflash driver
+
 ifeq ($(CONFIG_ESP32S3_SPIFLASH),y)
-CHIP_CSRCS += esp32s3_spiflash.c
-ifeq ($(CONFIG_ESP32S3_MTD),y)
-CHIP_CSRCS += esp32s3_spiflash_mtd.c
-endif
+  ifeq ($(filter y,$(CONFIG_ESP32S3_PARTITION_TABLE) 
$(CONFIG_ESP32S3_SPIRAM)),y)
+    CHIP_CSRCS += esp32s3_spiflash.c
+    CHIP_CSRCS += esp32s3_spiflash_mtd.c
+  endif
 endif
 
 ifeq ($(CONFIG_ESP32S3_PARTITION_TABLE),y)
-CHIP_CSRCS += esp32s3_partition.c
+CHIP_CSRCS +=  esp32s3_partition.c
 endif
 
 ifeq ($(CONFIG_ESP32S3_SPIRAM),y)
@@ -207,7 +209,7 @@ endif
 
 ESP_HAL_3RDPARTY_REPO = esp-hal-3rdparty
 ifndef ESP_HAL_3RDPARTY_VERSION
-       ESP_HAL_3RDPARTY_VERSION = 6782de1b073f93a54c501edf23d99a42a23d41ac
+       ESP_HAL_3RDPARTY_VERSION = 4eed03a15b2678a81dfd1ed0f3bde042b1fdd4c4
 endif
 
 ifndef ESP_HAL_3RDPARTY_URL
diff --git a/arch/xtensa/src/esp32s3/esp32s3_ble_adapter.c 
b/arch/xtensa/src/esp32s3/esp32s3_ble_adapter.c
index 7a2038f5742..5fb079aac39 100644
--- a/arch/xtensa/src/esp32s3/esp32s3_ble_adapter.c
+++ b/arch/xtensa/src/esp32s3/esp32s3_ble_adapter.c
@@ -51,13 +51,11 @@
 #include "hardware/esp32s3_rtccntl.h"
 #include "hardware/esp32s3_syscon.h"
 #include "hardware/wdev_reg.h"
-#include "rom/esp32s3_spiflash.h"
 #include "xtensa.h"
 #include "esp_attr.h"
 #include "esp32s3_irq.h"
 #include "esp32s3_rt_timer.h"
 #include "esp32s3_rtc.h"
-#include "esp32s3_spiflash.h"
 #include "espressif/esp_wireless.h"
 
 #include "esp_bt.h"
@@ -67,6 +65,7 @@
 #include "esp_private/esp_clk.h"
 #include "esp_private/phy.h"
 #include "esp_private/wifi.h"
+#include "esp_private/cache_utils.h"
 #include "esp_random.h"
 #include "esp_timer.h"
 #include "esp_rom_sys.h"
@@ -74,6 +73,7 @@
 #include "rom/ets_sys.h"
 #include "soc/soc_caps.h"
 #include "private/esp_coexist_internal.h"
+#include "soc/clk_tree_defs.h"
 
 #include "esp32s3_ble_adapter.h"
 
@@ -101,7 +101,7 @@
 
 #define BLE_PWR_HDL_INVL                 0xffff
 
-#ifdef CONFIG_ESP32S3_SPIFLASH
+#ifdef CONFIG_ESPRESSIF_SPIFLASH
 #  define BLE_TASK_EVENT_QUEUE_ITEM_SIZE  8
 #  define BLE_TASK_EVENT_QUEUE_LEN        8
 #endif
@@ -305,7 +305,7 @@ enum btdm_wakeup_src_e
 struct bt_sem_s
 {
   sem_t sem;
-#ifdef CONFIG_ESP32S3_SPIFLASH
+#ifdef CONFIG_ESPRESSIF_SPIFLASH
   struct esp_semcache_s sc;
 #endif
 };
@@ -649,7 +649,7 @@ static struct irqstate_list_s 
g_ble_int_flags[NR_IRQSTATE_FLAGS];
 
 /* Cached queue control variables */
 
-#ifdef CONFIG_ESP32S3_SPIFLASH
+#ifdef CONFIG_ESPRESSIF_SPIFLASH
 static struct esp_queuecache_s g_esp_queuecache;
 static uint8_t g_esp_queuecache_buffer[BLE_TASK_EVENT_QUEUE_ITEM_SIZE];
 #endif
@@ -962,7 +962,7 @@ static void *semphr_create_wrapper(uint32_t max, uint32_t 
init)
       return NULL;
     }
 
-#ifdef CONFIG_ESP32S3_SPIFLASH
+#ifdef CONFIG_ESPRESSIF_SPIFLASH
   esp_init_semcache(&bt_sem->sc, &bt_sem->sem);
 #endif
 
@@ -1033,7 +1033,7 @@ static int IRAM_ATTR semphr_give_from_isr_wrapper(void 
*semphr, void *hptw)
   int ret;
   struct bt_sem_s *bt_sem = (struct bt_sem_s *)semphr;
 
-#ifdef CONFIG_ESP32S3_SPIFLASH
+#ifdef CONFIG_ESPRESSIF_SPIFLASH
   if (spi_flash_cache_enabled())
     {
       ret = semphr_give_wrapper(bt_sem);
@@ -1275,7 +1275,7 @@ static void *queue_create_wrapper(uint32_t queue_len, 
uint32_t item_size)
 
   mq_adpt->msgsize = item_size;
 
-#ifdef CONFIG_ESP32S3_SPIFLASH
+#ifdef CONFIG_ESPRESSIF_SPIFLASH
   if (queue_len <= BLE_TASK_EVENT_QUEUE_LEN &&
       item_size == BLE_TASK_EVENT_QUEUE_ITEM_SIZE)
     {
@@ -2272,7 +2272,7 @@ static IRAM_ATTR int32_t esp_queue_send_generic(void 
*queue, void *item,
   struct timespec timeout;
   struct mq_adpt_s *mq_adpt = (struct mq_adpt_s *)queue;
 
-#ifdef CONFIG_ESP32S3_SPIFLASH
+#ifdef CONFIG_ESPRESSIF_SPIFLASH
   if (!spi_flash_cache_enabled())
     {
       esp_send_queuecache(&g_esp_queuecache, item, mq_adpt->msgsize);
@@ -3370,7 +3370,7 @@ int esp32s3_bt_controller_init(void)
 
   g_btdm_controller_status = ESP_BT_CONTROLLER_STATUS_INITED;
 
-#ifdef CONFIG_ESP32S3_SPIFLASH
+#ifdef CONFIG_ESPRESSIF_SPIFLASH
   if (esp_wireless_init() != OK)
     {
       return -EIO;
diff --git a/arch/xtensa/src/esp32s3/esp32s3_spi_timing.c 
b/arch/xtensa/src/esp32s3/esp32s3_spi_timing.c
index 9e46d63396c..ea544f0e282 100644
--- a/arch/xtensa/src/esp32s3/esp32s3_spi_timing.c
+++ b/arch/xtensa/src/esp32s3/esp32s3_spi_timing.c
@@ -33,7 +33,6 @@
 #include "hardware/esp32s3_iomux.h"
 #include "hardware/esp32s3_gpio.h"
 #include "hardware/esp32s3_gpio_sigmap.h"
-#include "rom/esp32s3_spiflash.h"
 #include "rom/opi_flash.h"
 
 #include "soc/spi_mem_reg.h"
diff --git a/arch/xtensa/src/esp32s3/esp32s3_start.c 
b/arch/xtensa/src/esp32s3/esp32s3_start.c
index 1910090b6f0..a96f5b0e58f 100644
--- a/arch/xtensa/src/esp32s3/esp32s3_start.c
+++ b/arch/xtensa/src/esp32s3/esp32s3_start.c
@@ -48,11 +48,12 @@
 #include "hardware/esp32s3_cache_memory.h"
 #include "hardware/esp32s3_system.h"
 #include "rom/esp32s3_libc_stubs.h"
-#include "rom/opi_flash.h"
-#include "rom/esp32s3_spiflash.h"
+#include "esp_private/spi_flash_os.h"
 #include "espressif/esp_loader.h"
 
 #include "esp_app_desc.h"
+#include "esp_private/esp_mmu_map_private.h"
+#include "esp_flash_internal.h"
 #include "hal/mmu_hal.h"
 #include "hal/mmu_types.h"
 #include "hal/cache_types.h"
@@ -359,6 +360,8 @@ noinstrument_function void noreturn_function IRAM_ATTR 
__esp32s3_start(void)
 
   esp32s3_wdt_early_deinit();
 
+  esp_flash_app_init();
+
   /* Initialize RTC controller parameters */
 
   esp32s3_rtc_init();
@@ -556,6 +559,8 @@ noinstrument_function void IRAM_ATTR __start(void)
 
   spi_flash_init_chip_state();
 
+  esp_mmu_map_init();
+
   __esp32s3_start();
 
   while (true); /* Should not return */
diff --git a/arch/xtensa/src/esp32s3/esp32s3_user.c 
b/arch/xtensa/src/esp32s3/esp32s3_user.c
index d15f0f748d5..cb1c43e9949 100644
--- a/arch/xtensa/src/esp32s3/esp32s3_user.c
+++ b/arch/xtensa/src/esp32s3/esp32s3_user.c
@@ -27,9 +27,8 @@
 #include <stdint.h>
 
 #include "xtensa.h"
-#ifdef CONFIG_ESP32S3_SPIFLASH
-#include "rom/esp32s3_spiflash.h"
-#include "esp32s3_spiflash.h"
+#ifdef CONFIG_ESPRESSIF_SPIFLASH
+#include "esp_private/cache_utils.h"
 #endif
 
 /****************************************************************************
@@ -65,12 +64,14 @@
 
 uint32_t *xtensa_user(int exccause, uint32_t *regs)
 {
-#ifdef CONFIG_ESP32S3_SPIFLASH
+#ifdef CONFIG_ESPRESSIF_SPIFLASH
+  int cpu = this_cpu();
+
   if (!spi_flash_cache_enabled())
     {
-      spiflash_resume_cache();
+      spi_flash_restore_cache(cpu, 0);
     }
-#endif /* CONFIG_ESP32S3_SPIFLASH */
+#endif /* CONFIG_ESPRESSIF_SPIFLASH */
 
   /* xtensa_user_panic never returns. */
 
diff --git a/arch/xtensa/src/esp32s3/hal.mk b/arch/xtensa/src/esp32s3/hal.mk
index 96d69556fd4..6ae08ae9e8a 100644
--- a/arch/xtensa/src/esp32s3/hal.mk
+++ b/arch/xtensa/src/esp32s3/hal.mk
@@ -124,6 +124,7 @@ CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)port$(DELIM)$(CHIP_SERIES)$(DELIM)sar_periph_ctrl.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)port$(DELIM)$(CHIP_SERIES)$(DELIM)cpu_region_protect.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)port$(DELIM)$(CHIP_SERIES)$(DELIM)esp_clk_tree.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)port$(DELIM)$(CHIP_SERIES)$(DELIM)io_mux.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)port$(DELIM)$(CHIP_SERIES)$(DELIM)rtc_clk.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)port$(DELIM)$(CHIP_SERIES)$(DELIM)rtc_init.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)port$(DELIM)$(CHIP_SERIES)$(DELIM)rtc_clk_init.c
@@ -135,6 +136,9 @@ CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)port$(DELIM)esp_clk_tree_common.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)regi2c_ctrl.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)sleep_modes.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)power_supply$(DELIM)brownout.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_mm$(DELIM)esp_mmu_map.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_mm$(DELIM)port$(DELIM)$(CHIP_SERIES)$(DELIM)ext_mem_layout.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_mm$(DELIM)esp_cache.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_phy$(DELIM)$(CHIP_SERIES)$(DELIM)phy_init_data.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_phy$(DELIM)src$(DELIM)phy_common.c
@@ -144,6 +148,8 @@ CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_efuse.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_system$(DELIM)esp_err.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_system$(DELIM)startup.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_system$(DELIM)startup_funcs.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_system$(DELIM)system_time.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_system$(DELIM)port$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)clk.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_system$(DELIM)port$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)system_internal.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)adc_hal_common.c
@@ -170,6 +176,10 @@ CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)uart_hal_iram.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)uart_hal.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)hal_utils.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)spi_flash_hal.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)spi_flash_hal_iram.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)spi_flash_hal_gpspi.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)spi_flash_encrypt_hal_iram.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)log_level$(DELIM)log_level.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)log_level$(DELIM)tag_log_level$(DELIM)tag_log_level.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)log_level$(DELIM)tag_log_level$(DELIM)linked_list$(DELIM)log_linked_list.c
@@ -177,6 +187,7 @@ CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)noos$(DELIM)log_lock.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)noos$(DELIM)log_timestamp.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)os$(DELIM)log_write.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)log$(DELIM)src$(DELIM)os$(DELIM)util.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)mbedtls$(DELIM)port$(DELIM)sha$(DELIM)core$(DELIM)esp_sha256.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)dport_access_common.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)dedic_gpio_periph.c
@@ -193,20 +204,40 @@ CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)mcpwm_periph.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)temperature_sensor_periph.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_wrap.c
-CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)flash_ops.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_hpm_enable.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)${CHIP_SERIES}$(DELIM)spi_flash_oct_flash_init.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_os_func_noos.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_os_func_app.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_generic.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_boya.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_gd.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_winbond.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_issi.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_mxic_opi.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_mxic.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_th.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)esp_flash_api.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)flash_ops.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)spi_flash_chip_drivers.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)memspi_host_driver.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)esp_flash_spi_init.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)flash_mmap.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)flash_brownout_hook.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)spi_flash$(DELIM)cache_utils.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)ulp$(DELIM)ulp_common$(DELIM)ulp_common.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)ulp$(DELIM)ulp_common$(DELIM)ulp_adc.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)ulp$(DELIM)ulp_riscv$(DELIM)ulp_riscv.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)ulp$(DELIM)ulp_riscv$(DELIM)ulp_riscv_lock.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)ulp$(DELIM)ulp_riscv$(DELIM)ulp_riscv_i2c.c
-CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)port$(DELIM)$(CHIP_SERIES)$(DELIM)io_mux.c
 
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)nuttx$(DELIM)src$(DELIM)components$(DELIM)esp_driver_gpio$(DELIM)src$(DELIM)rtc_io.c
 
 CHIP_ASRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_cache_writeback_esp32s3.S
 
+# Bootloader files
+
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)flash_encrypt.c
+
 ifeq ($(CONFIG_ESPRESSIF_SIMPLE_BOOT),y)
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)nuttx$(DELIM)src$(DELIM)bootloader_banner_wrap.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)bootloader_console.c
@@ -225,7 +256,6 @@ ifeq ($(CONFIG_ESPRESSIF_SIMPLE_BOOT),y)
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)esp_image_format.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)${CHIP_SERIES}$(DELIM)bootloader_soc.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)bootloader_sha.c
-  CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)flash_encrypt.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)${CHIP_SERIES}$(DELIM)uart_periph.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_uart.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_sys.c
diff --git a/boards/xtensa/esp32/common/scripts/esp32_sections.ld 
b/boards/xtensa/esp32/common/scripts/esp32_sections.ld
index e4b6a2a9395..bb7472f871d 100644
--- a/boards/xtensa/esp32/common/scripts/esp32_sections.ld
+++ b/boards/xtensa/esp32/common/scripts/esp32_sections.ld
@@ -221,15 +221,12 @@ SECTIONS
     *libarch.a:*log_write.*(.literal.esp_log_writev .text.esp_log_writev)
     *libarch.a:*cpu_region_protect.*(.text .text.* .literal .literal.*)
     *libarch.a:*flash_qio_mode.*(.text .text.* .literal .literal.*)
-    *libarch.a:*spi_flash_wrap.*(.text .text.* .literal .literal.*)
 
 #ifdef CONFIG_STACK_CANARIES
     *libc.a:lib_stackchk.*(.literal .text .literal.* .text.*)
 #endif
     *libarch.a:esp32_cpuindex.*(.literal .text .literal.* .text.*)
     *libarch.a:esp32_irq.*(.literal .text .literal.* .text.*)
-    *libarch.a:esp32_spicache.*(.literal .text .literal.* .text.*)
-    *libarch.a:esp32_spiflash.*(.literal .text .literal.* .text.*)
     *libarch.a:esp32_user.*(.literal .text .literal.* .text.*)
     *libarch.a:xtensa_assert.*(.literal .text .literal.* .text.*)
     *libarch.a:xtensa_cpuint.*(.literal .text .literal.* .text.*)
@@ -258,6 +255,22 @@ SECTIONS
     *libsched.a:sched_unlock.*(.literal .text .literal.* .text.*)
     *libsched.a:spinlock.*(.literal .text .literal.* .text.*)
 
+    *libarch.a:esp_spiflash.*(.literal .text .literal.* .text.*)
+    *libarch.a:esp_flash_api.*(.text .text.* .literal .literal.*)
+    *libarch.a:esp_flash_spi_init.*(.text .text.* .literal .literal.*)
+    *libarch.a:spi_flash_hal_iram.*(.literal .literal.* .text .text.*)
+    *libarch.a:spi_flash_encrypt_hal_iram.*(.text .text.* .literal .literal.*)
+    *libarch.a:spi_flash_hal_gpspi.*(.literal .literal.* .text .text.*)
+    *libarch.a:spi_flash_chip*.*(.literal .literal.* .text .text.*)
+    *libarch.a:spi_flash_wrap.*(.literal .literal.* .text .text.*)
+    *libarch.a:spi_flash_os_func_noos.*(.literal .literal.* .text .text.*)
+    *libarch.a:spi_flash_os_func_app.*(.literal .literal.* .text .text.*)
+    *libarch.a:flash_brownout_hook.*(.literal .literal.* .text .text.*)
+    *libarch.a:esp_cache.*(.literal .literal.* .text .text.*)
+    *libarch.a:cache_hal_esp32.*(.literal .literal.* .text .text.*)
+    *libarch.a:cache_utils.*(.literal .literal.* .text .text.*)
+    *libarch.a:memspi_host_driver.*(.literal .literal.* .text .text.*)
+
     *(.wifirxiram .wifirxiram.*)
     *(.wifi0iram .wifi0iram.*)
     *(.wifiorslpiram .wifiorslpiram.*)
@@ -347,8 +360,7 @@ SECTIONS
 #ifdef CONFIG_STACK_CANARIES
     *libc.a:lib_stackchk.*(.bss  .bss.*  COMMON)
 #endif
-    *libarch.a:esp32_spicache.*(.bss  .bss.*  COMMON)
-    *libarch.a:esp32_spiflash.*(.bss  .bss.*  COMMON)
+    *libarch.a:esp_spiflash.*(.bss  .bss.*  COMMON)
     *libarch.a:xtensa_cpupause.*(.bss  .bss.*  COMMON)
     *libarch.a:xtensa_copystate.*(.bss  .bss.*  COMMON)
     *libarch.a:xtensa_interruptcontext.*(.bss  .bss.*  COMMON)
@@ -411,8 +423,6 @@ SECTIONS
     *libsched.a:irq_csection.*(.rodata  .rodata.*)
     *libsched.a:irq_dispatch.*(.rodata  .rodata.*)
 
-    *libarch.a:esp32_spicache.*(.rodata  .rodata.*)
-    *libarch.a:esp32_spiflash.*(.rodata  .rodata.*)
     *libarch.a:*esp_loader.*(.rodata .rodata.*)
     *libarch.a:*brownout.*(.rodata .rodata.*)
     *libarch.a:*cpu.*(.rodata .rodata.*)
@@ -462,7 +472,21 @@ SECTIONS
     *libarch.a:*log_noos.*(.rodata .rodata.*)
     *libarch.a:*cpu_region_protect.*(.rodata .rodata.*)
     *libarch.a:*flash_qio_mode.*(.rodata .rodata.*)
-    *libarch.a:*spi_flash_wrap.*(.rodata .rodata.*)
+
+    *libarch.a:esp_flash_api.*(.rodata .rodata.*)
+    *libarch.a:esp_flash_spi_init.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_hal_iram.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_encrypt_hal_iram.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_hal_gpspi.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_chip*.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_wrap.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_os_func_noos.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_os_func_app.*(.rodata .rodata.*)
+    *libarch.a:flash_brownout_hook.*(.rodata .rodata.*)
+    *libarch.a:esp_cache.*(.rodata .rodata.*)
+    *libarch.a:cache_utils.*(.rodata .rodata.*)
+    *libarch.a:cache_hal_esp32.*(.rodata .rodata.*)
+    *libarch.a:memspi_host_driver.*(.rodata .rodata.*)
 
     _edata = ABSOLUTE(.);
     _data_end = ABSOLUTE(.);
@@ -526,12 +550,12 @@ SECTIONS
 
     . = ALIGN(4);
     _srodata = ABSOLUTE(.);
-    *(EXCLUDE_FILE (*libarch.a:esp32_spiflash.* esp32_start.*
+    *(EXCLUDE_FILE (*libarch.a:esp_spiflash.* esp32_start.*
                     *libarch.a:*esp_loader.*
                     *libarch.a:*uart_hal.*
                     *libarch.a:*mmu_hal.*
                     ) .rodata)
-    *(EXCLUDE_FILE (*libarch.a:esp32_spiflash.* esp32_start.*
+    *(EXCLUDE_FILE (*libarch.a:esp_spiflash.* esp32_start.*
                     *libarch.a:*esp_loader.*
                     *libarch.a:*uart_hal.*
                     *libarch.a:*mmu_hal.*
@@ -703,4 +727,22 @@ SECTIONS
     . = ALIGN (4);
     _srtcheap = ABSOLUTE(.);
   } >rtc_slow_seg AT>ROM
+
+  /*
+    * This section holds RTC data that should have fixed addresses.
+    * The data are not initialized at power-up and are retained during deep 
sleep.
+    */
+  .rtc_reserved (NOLOAD):
+  {
+    . = ALIGN(4);
+    _rtc_reserved_start = ABSOLUTE(.);
+    /* New data can only be added here to ensure existing data are not moved.
+        Because data have adhered to the end of the segment and code is relied 
on it.
+        >> put new data here << */
+
+    *(.rtc_timer_data_in_rtc_mem .rtc_timer_data_in_rtc_mem.*)
+    KEEP(*(.bootloader_data_rtc_mem .bootloader_data_rtc_mem.*))
+    _rtc_reserved_end = ABSOLUTE(.);
+  } > rtc_reserved_seg
+
 }
diff --git a/boards/xtensa/esp32/common/scripts/flat_memory.ld 
b/boards/xtensa/esp32/common/scripts/flat_memory.ld
index 3f4ab4daf75..bb4895fe12c 100644
--- a/boards/xtensa/esp32/common/scripts/flat_memory.ld
+++ b/boards/xtensa/esp32/common/scripts/flat_memory.ld
@@ -45,7 +45,9 @@
 #  define FLASH_SIZE 0x1000000
 #endif
 
-#define SRAM1_IRAM_LEN 0xa000
+#define SRAM1_IRAM_LEN        0xa000
+#define RTC_TIMER_RESERVE_RTC (24)
+#define RESERVE_RTC_MEM       (RTC_TIMER_RESERVE_RTC)
 
 MEMORY
 {
@@ -154,6 +156,8 @@ MEMORY
   rtc_slow_seg (RW) :    org = 0x50000000 + 
CONFIG_ESP32_ULP_COPROC_RESERVE_MEM,
                          len = 0x1000 - CONFIG_ESP32_ULP_COPROC_RESERVE_MEM
 
+  rtc_reserved_seg(RW) : org = 0x50000000 + 0x2000 - RESERVE_RTC_MEM, len = 
RESERVE_RTC_MEM
+
   /* External memory, including data and text */
 
   extmem_seg (RWX) :     org = 0x3f800000, len = 0x400000
diff --git a/boards/xtensa/esp32/common/scripts/kernel-space.ld 
b/boards/xtensa/esp32/common/scripts/kernel-space.ld
index 9d55b1b4bd9..fb0ab0e6c76 100644
--- a/boards/xtensa/esp32/common/scripts/kernel-space.ld
+++ b/boards/xtensa/esp32/common/scripts/kernel-space.ld
@@ -117,7 +117,8 @@ SECTIONS
     _iram_text_start = ABSOLUTE(.);
     *(.iram1 .iram1.*)
     *librtc.a:(.literal .text .literal.* .text.*)
-    *libkarch.a:esp32_spiflash.*(.literal .text .literal.* .text.*)
+    *libkarch.a:esp_spiflash.*(.literal .text .literal.* .text.*)
+    *libkarch.a:*esp_clk.*(.text .text.* .literal .literal.*)
     *libkarch.a:xtensa_cpupause.*(.literal .text .literal.* .text.*)
     *libkarch.a:xtensa_copystate.*(.literal .text .literal.* .text.*)
     *libkarch.a:xtensa_interruptcontext.*(.literal .text .literal.* .text.*)
@@ -177,7 +178,7 @@ SECTIONS
     *(.share.mem)
     *(.gnu.linkonce.b.*)
     *(COMMON)
-    *libkarch.a:esp32_spiflash.*(.bss  .bss.*  COMMON)
+    *libkarch.a:esp_spiflash.*(.bss  .bss.*  COMMON)
     *libkarch.a:xtensa_cpupause.*(.bss  .bss.*  COMMON)
     *libkarch.a:xtensa_copystate.*(.bss  .bss.*  COMMON)
     *libkarch.a:xtensa_interruptcontext.*(.bss  .bss.*  COMMON)
@@ -230,7 +231,8 @@ SECTIONS
     KEEP (*(.jcr))
     *(.dram1 .dram1.*)
     *libphy.a:(.rodata  .rodata.*)
-    *libkarch.a:esp32_spiflash.*(.rodata  .rodata.*)
+    *libkarch.a:esp_spiflash.*(.rodata  .rodata.*)
+    *libkarch.a:*esp_clk.*(.rodata .rodata.*)
     *libkarch.a:xtensa_cpupause.*(.rodata  .rodata.*)
     *libkarch.a:xtensa_copystate.*(.rodata  .rodata.*)
     *libkarch.a:xtensa_interruptcontext.*(.rodata  .rodata.*)
@@ -332,4 +334,21 @@ SECTIONS
     _text_end = ABSOLUTE(.);
     _etext = .;
   } >KIROM
+
+  /*
+    * This section holds RTC data that should have fixed addresses.
+    * The data are not initialized at power-up and are retained during deep 
sleep.
+    */
+  .rtc_reserved (NOLOAD):
+  {
+    . = ALIGN(4);
+    _rtc_reserved_start = ABSOLUTE(.);
+    /* New data can only be added here to ensure existing data are not moved.
+        Because data have adhered to the end of the segment and code is relied 
on it.
+        >> put new data here << */
+
+    *(.rtc_timer_data_in_rtc_mem .rtc_timer_data_in_rtc_mem.*)
+    KEEP(*(.bootloader_data_rtc_mem .bootloader_data_rtc_mem.*))
+    _rtc_reserved_end = ABSOLUTE(.);
+  } > rtc_reserved_seg
 }
diff --git a/boards/xtensa/esp32/common/src/esp32_board_spiflash.c 
b/boards/xtensa/esp32/common/src/esp32_board_spiflash.c
index 1a9d2bd38c3..1f228c13689 100644
--- a/boards/xtensa/esp32/common/src/esp32_board_spiflash.c
+++ b/boards/xtensa/esp32/common/src/esp32_board_spiflash.c
@@ -44,7 +44,8 @@
 #include <nuttx/fs/nxffs.h>
 #endif
 
-#include "esp32_spiflash.h"
+#include "espressif/esp_spiflash.h"
+#include "espressif/esp_spiflash_mtd.h"
 #include "esp32_board_spiflash.h"
 
 /****************************************************************************
@@ -116,8 +117,7 @@ static int init_ota_partitions(void)
   for (int i = 0; i < nitems(g_ota_partition_table); ++i)
     {
       const struct partition_s *part = &g_ota_partition_table[i];
-      mtd = esp32_spiflash_alloc_mtdpart(part->firstblock, part->blocksize,
-                                         OTA_ENCRYPT);
+      mtd = esp_spiflash_alloc_mtdpart(part->firstblock, part->blocksize);
 
       ret = register_mtddriver(part->name, mtd, 0755, NULL);
       if (ret < 0)
@@ -350,9 +350,8 @@ static int init_storage_partition(void)
   int ret = OK;
   struct mtd_dev_s *mtd;
 
-  mtd = esp32_spiflash_alloc_mtdpart(CONFIG_ESP32_STORAGE_MTD_OFFSET,
-                                     CONFIG_ESP32_STORAGE_MTD_SIZE,
-                                     STORAGE_ENCRYPT);
+  mtd = esp_spiflash_alloc_mtdpart(CONFIG_ESP32_STORAGE_MTD_OFFSET,
+                                   CONFIG_ESP32_STORAGE_MTD_SIZE);
   if (!mtd)
     {
       syslog(LOG_ERR, "ERROR: Failed to alloc MTD partition of SPI Flash\n");
@@ -446,7 +445,7 @@ int board_spiflash_init(void)
 {
   int ret = OK;
 
-  ret = esp32_spiflash_init();
+  ret = esp_spiflash_init();
   if (ret < 0)
     {
       return ret;
diff --git a/boards/xtensa/esp32/esp32-devkitc/configs/spiflash/defconfig 
b/boards/xtensa/esp32/esp32-devkitc/configs/spiflash/defconfig
index 1bd233c2308..c0a6589bfce 100644
--- a/boards/xtensa/esp32/esp32-devkitc/configs/spiflash/defconfig
+++ b/boards/xtensa/esp32/esp32-devkitc/configs/spiflash/defconfig
@@ -15,6 +15,7 @@ CONFIG_ARCH_BOARD_ESP32_DEVKITC=y
 CONFIG_ARCH_CHIP="esp32"
 CONFIG_ARCH_CHIP_ESP32=y
 CONFIG_ARCH_CHIP_ESP32WROVER=y
+CONFIG_ARCH_INTERRUPTSTACK=2048
 CONFIG_ARCH_STACKDUMP=y
 CONFIG_ARCH_XTENSA=y
 CONFIG_BOARD_LOOPSPERMSEC=16717
@@ -30,7 +31,7 @@ CONFIG_INIT_ENTRYPOINT="nsh_main"
 CONFIG_INIT_STACKSIZE=3072
 CONFIG_INTELHEX_BINARY=y
 CONFIG_LINE_MAX=64
-CONFIG_MM_REGIONS=3
+CONFIG_MM_REGIONS=4
 CONFIG_NSH_ARCHINIT=y
 CONFIG_NSH_BUILTIN_APPS=y
 CONFIG_NSH_DISABLE_LOSMART=y
@@ -41,6 +42,8 @@ CONFIG_RAM_SIZE=114688
 CONFIG_RAM_START=0x20000000
 CONFIG_RR_INTERVAL=200
 CONFIG_SCHED_WAITPID=y
+CONFIG_SMP=y
+CONFIG_SMP_NCPUS=2
 CONFIG_SPI=y
 CONFIG_START_DAY=6
 CONFIG_START_MONTH=12
diff --git a/boards/xtensa/esp32s2/common/scripts/esp32s2_sections.ld 
b/boards/xtensa/esp32s2/common/scripts/esp32s2_sections.ld
index 814148d0d77..5cc7907c2d7 100644
--- a/boards/xtensa/esp32s2/common/scripts/esp32s2_sections.ld
+++ b/boards/xtensa/esp32s2/common/scripts/esp32s2_sections.ld
@@ -163,7 +163,6 @@ SECTIONS
     *libpp.a:wifi_or_slp_iram.*(.literal .text .literal.* .text.*)
     *libpp.a:wifi_slp_rx_iram.*(.literal .text .literal.* .text.*)
     *libarch.a:*esp_loader.*(.literal .text .literal.* .text.*)
-    *libarch.a:esp32s2_spiflash.*(.literal .text .literal.* .text.*)
     *libarch.a:*brownout_hal.*(.text .text.* .literal .literal.*)
     *libarch.a:*cpu.*(.text .text.* .literal .literal.*)
     *libarch.a:*gpio_hal.*(.text .text.* .literal .literal.*)
@@ -227,7 +226,20 @@ SECTIONS
     *libarch.a:*log_write.*(.literal.esp_log_writev .text.esp_log_writev)
     *libarch.a:*cpu_region_protect.*(.text .text.* .literal .literal.*)
     *libarch.a:*flash_qio_mode.*(.text .text.* .literal .literal.*)
-    *libarch.a:*spi_flash_wrap.*(.text .text.* .literal .literal.*)
+    *libarch.a:esp_spiflash.*(.literal .text .literal.* .text.*)
+    *libarch.a:esp_flash_api.*(.text .text.* .literal .literal.*)
+    *libarch.a:esp_flash_spi_init.*(.text .text.* .literal .literal.*)
+    *libarch.a:spi_flash_hal_iram.*(.literal .literal.* .text .text.*)
+    *libarch.a:spi_flash_encrypt_hal_iram.*(.text .text.* .literal .literal.*)
+    *libarch.a:spi_flash_hal_gpspi.*(.literal .literal.* .text .text.*)
+    *libarch.a:spi_flash_chip*.*(.literal .literal.* .text .text.*)
+    *libarch.a:spi_flash_wrap.*(.literal .literal.* .text .text.*)
+    *libarch.a:spi_flash_os_func_noos.*(.literal .literal.* .text .text.*)
+    *libarch.a:spi_flash_os_func_app.*(.literal .literal.* .text .text.*)
+    *libarch.a:flash_brownout_hook.*(.literal .literal.* .text .text.*)
+    *libarch.a:esp_cache.*(.literal .literal.* .text .text.*)
+    *libarch.a:cache_utils.*(.literal .literal.* .text .text.*)
+    *libarch.a:memspi_host_driver.*(.literal .literal.* .text .text.*)
 
     *libc.a:sq_remlast.*(.literal .text .literal.* .text.*)
 
@@ -328,7 +340,6 @@ SECTIONS
     esp32s2_region.*(.rodata .rodata.*)
 
     *libarch.a:*esp_loader.*(.rodata .rodata.*)
-    *libarch.a:esp32s2_spiflash.*(.rodata .rodata.*)
     *libarch.a:*brownout.*(.rodata .rodata.*)
     *libarch.a:*cpu.*(.rodata .rodata.*)
     *libarch.a:*gpio_hal.*(.rodata .rodata.*)
@@ -381,7 +392,19 @@ SECTIONS
     *libarch.a:*log_noos.*(.rodata .rodata.*)
     *libarch.a:*cpu_region_protect.*(.rodata .rodata.*)
     *libarch.a:*flash_qio_mode.*(.rodata .rodata.*)
-    *libarch.a:*spi_flash_wrap.*(.rodata .rodata.*)
+    *libarch.a:esp_flash_api.*(.rodata .rodata.*)
+    *libarch.a:esp_flash_spi_init.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_hal_iram.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_encrypt_hal_iram.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_hal_gpspi.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_chip*.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_wrap.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_os_func_noos.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_os_func_app.*(.rodata .rodata.*)
+    *libarch.a:flash_brownout_hook.*(.rodata .rodata.*)
+    *libarch.a:esp_cache.*(.rodata .rodata.*)
+    *libarch.a:cache_utils.*(.rodata .rodata.*)
+    *libarch.a:memspi_host_driver.*(.rodata .rodata.*)
 
     *libsched.a:irq_dispatch.*(.rodata .rodata.*)
     *libsched.a:sched_lock.*(.rodata .rodata.*)
@@ -449,12 +472,10 @@ SECTIONS
     _srodata = ABSOLUTE(.);
     *(EXCLUDE_FILE (esp32s2_start.* esp32s2_region.*
                     *libarch.a:*esp_loader.*
-                    *libarch.a:esp32s2_spiflash.*
                     *libarch.a:*cache_hal.* *libarch.a:*mmu_hal.*
                     *libarch.a:*mpu_hal.*) .rodata)
     *(EXCLUDE_FILE (esp32s2_start.* esp32s2_region.*
                     *libarch.a:*esp_loader.*
-                    *libarch.a:esp32s2_spiflash.*
                     *libarch.a:*cache_hal.* *libarch.a:*mmu_hal.*
                     *libarch.a:*mpu_hal.*) .rodata.*)
 
diff --git a/boards/xtensa/esp32s2/common/src/esp32s2_board_spiflash.c 
b/boards/xtensa/esp32s2/common/src/esp32s2_board_spiflash.c
index 5881b7ed6d5..bc8b505587d 100644
--- a/boards/xtensa/esp32s2/common/src/esp32s2_board_spiflash.c
+++ b/boards/xtensa/esp32s2/common/src/esp32s2_board_spiflash.c
@@ -51,14 +51,6 @@
  * Pre-processor Definitions
  ****************************************************************************/
 
-#ifndef CONFIG_ESP32S2_STORAGE_MTD_OFFSET
-#  define CONFIG_ESP32S2_STORAGE_MTD_OFFSET 0x180000
-#endif
-
-#ifndef CONFIG_ESP32S2_STORAGE_MTD_SIZE
-#  define CONFIG_ESP32S2_STORAGE_MTD_SIZE 0x100000
-#endif
-
 /****************************************************************************
  * Private Types
  ****************************************************************************/
@@ -360,8 +352,8 @@ static int init_storage_partition(void)
   int ret = OK;
   struct mtd_dev_s *mtd;
 
-  mtd = esp_spiflash_alloc_mtdpart(CONFIG_ESP32S2_STORAGE_MTD_OFFSET,
-                                   CONFIG_ESP32S2_STORAGE_MTD_SIZE);
+  mtd = esp_spiflash_alloc_mtdpart(CONFIG_ESPRESSIF_STORAGE_MTD_OFFSET,
+                                   CONFIG_ESPRESSIF_STORAGE_MTD_SIZE);
   if (!mtd)
     {
       syslog(LOG_ERR, "ERROR: Failed to alloc MTD partition of SPI Flash\n");
diff --git a/boards/xtensa/esp32s3/common/Kconfig 
b/boards/xtensa/esp32s3/common/Kconfig
index 5dc04c4e916..949fce11f05 100644
--- a/boards/xtensa/esp32s3/common/Kconfig
+++ b/boards/xtensa/esp32s3/common/Kconfig
@@ -33,7 +33,7 @@ config ESP32S3_SPEED_UP_ISR
 config ESP32S3_STORAGE_MTD_OFFSET
        hex "Storage MTD base address in SPI Flash"
        default 0x180000 if !ESP32S3_HAVE_OTA_PARTITION
-       default 0x250000 if ESP32S3_HAVE_OTA_PARTITION
+       default 0x260000 if ESP32S3_HAVE_OTA_PARTITION
        depends on ESP32S3_MTD
        ---help---
                MTD base address in SPI Flash.
diff --git a/boards/xtensa/esp32s3/common/scripts/esp32s3_sections.ld 
b/boards/xtensa/esp32s3/common/scripts/esp32s3_sections.ld
index fd16571f3fa..598609c4c76 100644
--- a/boards/xtensa/esp32s3/common/scripts/esp32s3_sections.ld
+++ b/boards/xtensa/esp32s3/common/scripts/esp32s3_sections.ld
@@ -296,6 +296,20 @@ SECTIONS
     *libarch.a:*spi_flash_wrap.*(.text .text.* .literal .literal.*)
     *libarch.a:*spi_flash_oct_flash_init.*(.text .text.* .literal .literal.*)
     *libarch.a:*spi_flash_hpm_enable.*(.text .text.* .literal .literal.*)
+    *libarch.a:esp_spiflash.*(.literal .text .literal.* .text.*)
+    *libarch.a:esp_flash_api.*(.text .text.* .literal .literal.*)
+    *libarch.a:esp_flash_spi_init.*(.text .text.* .literal .literal.*)
+    *libarch.a:spi_flash_hal_iram.*(.literal .literal.* .text .text.*)
+    *libarch.a:spi_flash_encrypt_hal_iram.*(.text .text.* .literal .literal.*)
+    *libarch.a:spi_flash_hal_gpspi.*(.literal .literal.* .text .text.*)
+    *libarch.a:spi_flash_chip*.*(.literal .literal.* .text .text.*)
+    *libarch.a:spi_flash_wrap.*(.literal .literal.* .text .text.*)
+    *libarch.a:spi_flash_os_func_noos.*(.literal .literal.* .text .text.*)
+    *libarch.a:spi_flash_os_func_app.*(.literal .literal.* .text .text.*)
+    *libarch.a:flash_brownout_hook.*(.literal .literal.* .text .text.*)
+    *libarch.a:esp_cache.*(.literal .literal.* .text .text.*)
+    *libarch.a:cache_utils.*(.literal .literal.* .text .text.*)
+    *libarch.a:memspi_host_driver.*(.literal .literal.* .text .text.*)
 
     *libc.a:*lib_instrument.*(.text .text.* .literal .literal.*)
 
@@ -433,6 +447,7 @@ SECTIONS
     *libsched.a:*sched_get_stackinfo.*(.rodata .rodata.*)
     *libarch.a:*esp_loader.*(.rodata .rodata.*)
     *libarch.a:esp32s3_spiflash.*(.rodata .rodata.*)
+    *libarch.a:esp_spiflash.*(.rodata .rodata.*)
     *libarch.a:*brownout.*(.rodata .rodata.*)
     *libarch.a:*cpu.*(.rodata .rodata.*)
     *libarch.a:*gpio_hal.*(.rodata .rodata.*)
@@ -495,6 +510,19 @@ SECTIONS
     *libarch.a:*spi_flash_wrap.*(.rodata .rodata.*)
     *libarch.a:*spi_flash_oct_flash_init.*(.rodata .rodata.*)
     *libarch.a:*spi_flash_hpm_enable.*(.rodata .rodata.*)
+    *libarch.a:esp_flash_api.*(.rodata .rodata.*)
+    *libarch.a:esp_flash_spi_init.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_hal_iram.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_encrypt_hal_iram.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_hal_gpspi.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_chip*.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_wrap.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_os_func_noos.*(.rodata .rodata.*)
+    *libarch.a:spi_flash_os_func_app.*(.rodata .rodata.*)
+    *libarch.a:flash_brownout_hook.*(.rodata .rodata.*)
+    *libarch.a:esp_cache.*(.rodata .rodata.*)
+    *libarch.a:cache_utils.*(.rodata .rodata.*)
+    *libarch.a:memspi_host_driver.*(.rodata .rodata.*)
 
     . = ALIGN(4);
     _edata = ABSOLUTE(.);
diff --git a/boards/xtensa/esp32s3/common/src/esp32s3_board_spiflash.c 
b/boards/xtensa/esp32s3/common/src/esp32s3_board_spiflash.c
index d129e29f600..6619ff4b8e6 100644
--- a/boards/xtensa/esp32s3/common/src/esp32s3_board_spiflash.c
+++ b/boards/xtensa/esp32s3/common/src/esp32s3_board_spiflash.c
@@ -43,8 +43,13 @@
 #include <nuttx/fs/nxffs.h>
 #include <nuttx/fs/partition.h>
 
-#include "esp32s3_spiflash.h"
-#include "esp32s3_spiflash_mtd.h"
+#if defined(CONFIG_ESP32S3_SPIRAM) || defined(CONFIG_ESP32S3_PARTITION_TABLE)
+#  include "esp32s3_spiflash.h"
+#  include "esp32s3_spiflash_mtd.h"
+#else
+#  include "espressif/esp_spiflash.h"
+#  include "espressif/esp_spiflash_mtd.h"
+#endif
 
 /****************************************************************************
  * Pre-processor Definitions
@@ -123,8 +128,12 @@ static int init_ota_partitions(void)
   for (int i = 0; i < nitems(g_ota_partition_table); ++i)
     {
       const struct partition_s *part = &g_ota_partition_table[i];
+#if defined(CONFIG_ESP32S3_SPIRAM) || defined(CONFIG_ESP32S3_PARTITION_TABLE)
       mtd = esp32s3_spiflash_alloc_mtdpart(part->firstblock, part->blocksize,
                                            OTA_ENCRYPT);
+#else
+      mtd = esp_spiflash_alloc_mtdpart(part->firstblock, part->blocksize);
+#endif
 
       ret = register_mtddriver(part->name, mtd, 0755, NULL);
       if (ret < 0)
@@ -358,9 +367,14 @@ static int init_storage_partition(void)
   int ret = OK;
   struct mtd_dev_s *mtd;
 
+#if defined(CONFIG_ESP32S3_SPIRAM) || defined(CONFIG_ESP32S3_PARTITION_TABLE)
   mtd = esp32s3_spiflash_alloc_mtdpart(CONFIG_ESP32S3_STORAGE_MTD_OFFSET,
                                        CONFIG_ESP32S3_STORAGE_MTD_SIZE,
-                                       false);
+                                       OTA_ENCRYPT);
+#else
+  mtd = esp_spiflash_alloc_mtdpart(CONFIG_ESP32S3_STORAGE_MTD_OFFSET,
+                                   CONFIG_ESP32S3_STORAGE_MTD_SIZE);
+#endif
   if (!mtd)
     {
       syslog(LOG_ERR, "ERROR: Failed to alloc MTD partition of SPI Flash\n");
@@ -435,7 +449,11 @@ int board_spiflash_init(void)
 {
   int ret = OK;
 
+#if defined(CONFIG_ESP32S3_SPIRAM) || defined(CONFIG_ESP32S3_PARTITION_TABLE)
   ret = esp32s3_spiflash_init();
+#else
+  ret = esp_spiflash_init();
+#endif
   if (ret < 0)
     {
       return ret;
diff --git a/boards/xtensa/esp32s3/esp32s3-devkit/configs/spiflash/defconfig 
b/boards/xtensa/esp32s3/esp32s3-devkit/configs/spiflash/defconfig
index dacd68f8343..070f890e095 100644
--- a/boards/xtensa/esp32s3/esp32s3-devkit/configs/spiflash/defconfig
+++ b/boards/xtensa/esp32s3/esp32s3-devkit/configs/spiflash/defconfig
@@ -28,7 +28,6 @@ CONFIG_ESP32S3_UART0=y
 CONFIG_FS_PROCFS=y
 CONFIG_HAVE_CXX=y
 CONFIG_HAVE_CXXINITIALIZE=y
-CONFIG_HOST_MACOS=y
 CONFIG_IDLETHREAD_STACKSIZE=3072
 CONFIG_INIT_ENTRYPOINT="nsh_main"
 CONFIG_INIT_STACKSIZE=3072
@@ -44,6 +43,8 @@ CONFIG_RAM_SIZE=114688
 CONFIG_RAM_START=0x20000000
 CONFIG_RR_INTERVAL=200
 CONFIG_SCHED_WAITPID=y
+CONFIG_SMP=y
+CONFIG_SMP_NCPUS=2
 CONFIG_START_DAY=6
 CONFIG_START_MONTH=12
 CONFIG_START_YEAR=2011

Reply via email to