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 4ccae59e69d1fe7976435e549791e988f9f58199
Author: Filipe Cavalcanti <[email protected]>
AuthorDate: Mon Sep 22 09:36:20 2025 -0300

    arch/risc-v: update SPI Flash driver for ESP32-C3|C6|H2
    
    Updates the SPI Flash driver used for user storage MTD.
    Updates board linker script and bring up.
    
    Signed-off-by: Filipe Cavalcanti <[email protected]>
---
 arch/risc-v/src/common/espressif/Kconfig           |  67 +--
 arch/risc-v/src/common/espressif/Make.defs         |   5 +-
 arch/risc-v/src/common/espressif/esp_spiflash.c    | 587 ++++++---------------
 arch/risc-v/src/common/espressif/esp_spiflash.h    |  97 +---
 .../risc-v/src/common/espressif/esp_spiflash_mtd.c |  86 +--
 arch/risc-v/src/common/espressif/esp_start.c       |   8 +
 arch/risc-v/src/esp32c3/hal_esp32c3.mk             |  33 +-
 arch/risc-v/src/esp32c6/hal_esp32c6.mk             |  28 +-
 arch/risc-v/src/esp32h2/hal_esp32h2.mk             |  28 +-
 .../esp32c3/common/scripts/esp32c3_sections.ld     |  29 +-
 .../esp32c6/common/scripts/esp32c6_sections.ld     |  28 +-
 .../risc-v/esp32c6/common/src/esp_board_spiflash.c |   6 +-
 .../esp32h2/common/scripts/esp32h2_sections.ld     |  26 +
 13 files changed, 392 insertions(+), 636 deletions(-)

diff --git a/arch/risc-v/src/common/espressif/Kconfig 
b/arch/risc-v/src/common/espressif/Kconfig
index bc27eb2d20c..6c4b6693849 100644
--- a/arch/risc-v/src/common/espressif/Kconfig
+++ b/arch/risc-v/src/common/espressif/Kconfig
@@ -473,8 +473,11 @@ config ESPRESSIF_SPI_BITBANG
                Software implemented SPI peripheral with GPIOs. Suggested to 
use if SPI peripheral is already in use.
 
 config ESPRESSIF_SPIFLASH
-       bool "SPI Flash"
+       bool "SPI Flash (User Storage)"
        default n
+       ---help---
+               Enable SPI Flash driver for general storage support. This allows
+               mounting an MTD partition at a configurable region in flash.
 
 config ESPRESSIF_DMA
        bool "General DMA (GDMA)"
@@ -1823,35 +1826,6 @@ config ESPRESSIF_FLASH_MODE_QOUT
 
 endchoice # ESPRESSIF_FLASH_MODE
 
-if ESPRESSIF_SPIFLASH
-comment "General storage MTD configuration"
-
-config ESPRESSIF_MTD
-       bool "MTD driver"
-       default y
-       select MTD
-       select MTD_BYTE_WRITE
-       select MTD_PARTITION
-       ---help---
-               Initialize an MTD driver for the SPI Flash, which will
-               add an entry at /dev for application access from userspace.
-
-config ESPRESSIF_SPIFLASH_MTD_BLKSIZE
-       int "Storage MTD block size"
-       default 64
-       depends on ESPRESSIF_MTD
-       ---help---
-               Block size for MTD driver in kB. This size must be divisible by 
2
-
-config ESPRESSIF_STORAGE_MTD_DEBUG
-       bool "Storage MTD Debug"
-       default n
-       depends on ESPRESSIF_MTD && DEBUG_FS_INFO
-       ---help---
-               If this option is enabled, Storage MTD driver read and write 
functions
-               will output input parameters and return values (if applicable).
-endif # ESPRESSIF_SPIFLASH
-
 choice ESPRESSIF_FLASH_FREQ
        prompt "SPI Flash frequency"
        default ESPRESSIF_FLASH_FREQ_80M if ARCH_CHIP_ESP32C3_GENERIC || 
ARCH_CHIP_ESP32C6
@@ -1916,6 +1890,36 @@ config ESPRESSIF_SPI_FLASH_USE_32BIT_ADDRESS
                of functions in ROM, so that SPI flash driver can access full
                32-bit address.
 
+endmenu # SPI Flash Configuration
+
+if ESPRESSIF_SPIFLASH
+menu "User Storage MTD Configuration"
+
+config ESPRESSIF_MTD
+       bool "MTD driver"
+       default y
+       select MTD
+       select MTD_BYTE_WRITE
+       select MTD_PARTITION
+       ---help---
+               Initialize an MTD driver for the SPI Flash, which will
+               add an entry at /dev for application access from userspace.
+
+config ESPRESSIF_SPIFLASH_MTD_BLKSIZE
+       int "Storage MTD block size"
+       default 64
+       depends on ESPRESSIF_MTD
+       ---help---
+               Block size for MTD driver in kB. This size must be divisible by 
2
+
+config ESPRESSIF_STORAGE_MTD_DEBUG
+       bool "Storage MTD Debug"
+       default n
+       depends on ESPRESSIF_MTD && DEBUG_FS_INFO
+       ---help---
+               If this option is enabled, Storage MTD driver read and write 
functions
+               will output input parameters and return values (if applicable).
+
 config ESPRESSIF_STORAGE_MTD_OFFSET
        hex "Storage MTD base address in SPI Flash"
        default 0x180000 if !ESPRESSIF_BOOTLOADER_MCUBOOT
@@ -1931,7 +1935,8 @@ config ESPRESSIF_STORAGE_MTD_SIZE
        ---help---
                MTD size in SPI Flash.
 
-endmenu # SPI Flash Configuration
+endmenu # User Storage MTD Configuration
+endif # ESPRESSIF_SPIFLASH
 
 menu "RTC Configuration"
        depends on ESPRESSIF_RTC
diff --git a/arch/risc-v/src/common/espressif/Make.defs 
b/arch/risc-v/src/common/espressif/Make.defs
index 6021697719c..d5e8ab12bcc 100644
--- a/arch/risc-v/src/common/espressif/Make.defs
+++ b/arch/risc-v/src/common/espressif/Make.defs
@@ -183,6 +183,9 @@ ifeq ($(CONFIG_ESPRESSIF_USE_LP_CORE), y)
        CHIP_CSRCS += esp_ulp.c
 endif
 
+# Required for initialization hooks on common code
+
+LDFLAGS += -u esp_system_include_startup_funcs
 ifeq ($(CONFIG_ESPRESSIF_EFUSE),y)
        LDFLAGS += -u esp_efuse_startup_include_func
 endif
@@ -195,7 +198,7 @@ endif
 
 ESP_HAL_3RDPARTY_REPO   = esp-hal-3rdparty
 ifndef ESP_HAL_3RDPARTY_VERSION
-       ESP_HAL_3RDPARTY_VERSION = 84efb531f4cdf3162e91652357cac6a0be8dd73e
+       ESP_HAL_3RDPARTY_VERSION = 4eed03a15b2678a81dfd1ed0f3bde042b1fdd4c4
 endif
 
 ifndef ESP_HAL_3RDPARTY_URL
diff --git a/arch/risc-v/src/common/espressif/esp_spiflash.c 
b/arch/risc-v/src/common/espressif/esp_spiflash.c
index 365a2c49c2d..b6efa248140 100644
--- a/arch/risc-v/src/common/espressif/esp_spiflash.c
+++ b/arch/risc-v/src/common/espressif/esp_spiflash.c
@@ -25,579 +25,276 @@
  ****************************************************************************/
 
 #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 "riscv_internal.h"
-#include "riscv/rv_utils.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 "esp_irq.h"
-
-/****************************************************************************
- * 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 */
+#include <sched/sched.h>
 
-#  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
-
-/* SPI flash operation */
-
-#  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)
-#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)
+#include "esp_flash_internal.h"
+#include "esp_flash.h"
+#include "esp_flash_encrypt.h"
+#ifdef CONFIG_SMP
+#include "esp_private/cache_utils.h"
 #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
+ * Pre-processor Definitions
  ****************************************************************************/
 
-void spiflash_start(void);
-void spiflash_end(void);
-#ifndef CONFIG_ESPRESSIF_SPI_FLASH_USE_ROM_CODE
-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
+ * Name: spi_flash_op_block_task
  *
  * Description:
- *   Prepare for an SPIFLASH operation.
+ *   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.
- *
- ****************************************************************************/
-
-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;
-
-  esp_intr_noniram_disable();
-
-  s_flash_op_cache_state[cpu] = cache_suspend_icache() << 16;
-
-  leave_critical_section(flags);
-}
-
-/****************************************************************************
- * Name: spiflash_end
- *
- * Description:
- *   Undo all the steps of opstart.
- *
- * Input Parameters:
- *   None.
- *
- * 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.
+           */
+        }
 
-  esp_intr_noniram_enable();
-  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 */
+  FAR struct tcb_s *tcb;
+  int ret;
+  char *argv[2];
+  char arg1[32];
+  cpu_set_t cpuset;
 
-  spi_flash_ll_reset(dev);
+  snprintf(arg1, sizeof(arg1), "%p", &cpu);
+  argv[0] = arg1;
+  argv[1] = NULL;
 
-  while (!spi_flash_ll_host_idle(dev));
+  /* Allocate a TCB for the new task. */
 
-  /* 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)
+  tcb = kmm_zalloc(sizeof(struct tcb_s));
+  if (!tcb)
     {
-      spi_flash_ll_set_addr_bitlen(dev, address_bits);
-      spi_flash_ll_set_address(dev, address);
+      serr("ERROR: Failed to allocate TCB\n");
+      return -ENOMEM;
     }
 
-  /* Set dummy */
+  /* Setup the task type */
 
-  if (dummy_bits)
-    {
-      spi_flash_ll_set_dummy(dev, dummy_bits);
-    }
+  tcb->flags = TCB_FLAG_TTYPE_KERNEL | TCB_FLAG_FREE_TCB;
 
-  /* Set TX data */
+  /* Initialize the task */
 
-  if (tx_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_mosi_bitlen(dev, tx_bytes * 8);
-      spi_flash_ll_set_buffer_data(dev, tx_buffer, tx_bytes);
+      kmm_free(tcb);
+      return ret;
     }
 
-  /* Set RX data */
-
-  if (rx_bytes)
-    {
-      spi_flash_ll_set_miso_bitlen(dev, rx_bytes * 8);
-    }
-
-  /* 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 */
-
-  spi_flash_ll_user_start(dev, false);
-
-  /* Wait until transmission is done */
-
-  while (!spi_flash_ll_cmd_is_done(dev));
-
-  /* Get read data */
+  /* Set the affinity */
 
-  if (rx_bytes)
-    {
-      spi_flash_ll_get_buffer_data(dev, rx_buffer, rx_bytes);
-    }
-}
+  CPU_ZERO(&cpuset);
+  CPU_SET(cpu, &cpuset);
+  tcb->affinity = cpuset;
 
-/****************************************************************************
- * Name: wait_flash_idle
- *
- * Description:
- *   Wait until flash enters idle state
- *
- * Input Parameters:
- *   None.
- *
- * Returned Value:
- *   None.
- *
- ****************************************************************************/
+  /* Activate the task */
 
-static IRAM_ATTR void wait_flash_idle(void)
-{
-  uint32_t status;
+  nxtask_activate(tcb);
 
-  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.
- *
- ****************************************************************************/
-
-static IRAM_ATTR void enable_flash_write(void)
-{
-  uint32_t status;
-
-  do
-    {
-      SEND_CMD8_TO_FLASH(FLASH_CMD_WREN);
-      READ_SR1_FROM_FLASH(FLASH_CMD_RDSR, &status);
-
-      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
+    {
+      ret = esp_flash_read_encrypted(NULL, address, buffer, length);
     }
 
-  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);
+    }
+  else
+    {
+      ret = esp_flash_write_encrypted(NULL, address, buffer, length);
     }
 
-  wait_flash_idle();
-  disable_flash_write();
-  spi_flash_check_and_flush_cache(start_address, size);
-
-  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();
-  spi_flash_check_and_flush_cache(dest_addr, size);
-
-  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.
@@ -609,11 +306,25 @@ IRAM_ATTR int spi_flash_write(uint32_t dest_addr,
 
 int esp_spiflash_init(void)
 {
-  extern void spi_flash_guard_set(const struct spiflash_guard_funcs *);
+  int ret = OK;
+  int cpu;
 
-  nxmutex_init(&s_flash_op_mutex);
+#ifdef CONFIG_SMP
+  sched_lock();
 
-  spi_flash_guard_set(&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/risc-v/src/common/espressif/esp_spiflash.h 
b/arch/risc-v/src/common/espressif/esp_spiflash.h
index d74eb2d934a..0d29a289455 100644
--- a/arch/risc-v/src/common/espressif/esp_spiflash.h
+++ b/arch/risc-v/src/common/espressif/esp_spiflash.h
@@ -30,8 +30,6 @@
 #include <nuttx/config.h>
 
 #include <sys/types.h>
-#include <stdint.h>
-#include <nuttx/mtd/mtd.h>
 
 #ifndef __ASSEMBLY__
 
@@ -48,122 +46,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.
+ *   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.
+ *   start   - Starting offset for flash erase.
+ *   length  - Length of data in bytes.
  *
  * 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 start, uint32_t length);
 
 /****************************************************************************
- * Name: spi_flash_write
+ * Name: esp_spiflash_write
  *
  * Description:
- *   Write data to Flash.
+ *   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/risc-v/src/common/espressif/esp_spiflash_mtd.c 
b/arch/risc-v/src/common/espressif/esp_spiflash_mtd.c
index 3708c348112..1cd1f8517bb 100644
--- a/arch/risc-v/src/common/espressif/esp_spiflash_mtd.c
+++ b/arch/risc-v/src/common/espressif/esp_spiflash_mtd.c
@@ -148,32 +148,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;
 }
 
@@ -198,27 +182,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;
 }
 
@@ -245,28 +215,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;
 }
 
@@ -292,7 +247,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);
 
@@ -301,25 +255,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;
 }
 
@@ -347,28 +288,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/risc-v/src/common/espressif/esp_start.c 
b/arch/risc-v/src/common/espressif/esp_start.c
index 995c72bc8ec..1c1199efef7 100644
--- a/arch/risc-v/src/common/espressif/esp_start.c
+++ b/arch/risc-v/src/common/espressif/esp_start.c
@@ -43,6 +43,7 @@
 #include "esp_clk_internal.h"
 #include "esp_private/rtc_clk.h"
 #include "esp_cpu.h"
+#include "esp_private/esp_mmu_map_private.h"
 #include "esp_private/brownout.h"
 #include "hal/wdt_hal.h"
 #include "hal/mmu_hal.h"
@@ -70,6 +71,7 @@
 #endif
 
 #include "esp_private/startup_internal.h"
+#include "esp_private/spi_flash_os.h"
 
 /****************************************************************************
  * Pre-processor Definitions
@@ -488,6 +490,12 @@ void __esp_start(void)
   esp_cpu_configure_region_protection();
 #endif
 
+  /* Configure SPI Flash chip state */
+
+  spi_flash_init_chip_state();
+
+  esp_mmu_map_init();
+
   /* Configures the CPU clock, RTC slow and fast clocks, and performs
    * RTC slow clock calibration.
    */
diff --git a/arch/risc-v/src/esp32c3/hal_esp32c3.mk 
b/arch/risc-v/src/esp32c3/hal_esp32c3.mk
index 1a9750b7924..7672ee051f5 100644
--- a/arch/risc-v/src/esp32c3/hal_esp32c3.mk
+++ b/arch/risc-v/src/esp32c3/hal_esp32c3.mk
@@ -45,6 +45,7 @@ INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY
 INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)include$(DELIM)esp_private
 INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)include$(DELIM)soc
 INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)ldo$(DELIM)include
+INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)mspi_timing_tuning$(DELIM)include
 INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)port$(DELIM)include
 INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)port$(DELIM)$(CHIP_SERIES)$(DELIM)include
 INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)port$(DELIM)$(CHIP_SERIES)$(DELIM)private_include
@@ -140,7 +141,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)$(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)systimer.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)esp_cache.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_phy$(DELIM)src$(DELIM)lib_printf.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
@@ -148,6 +151,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_systimer.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
@@ -175,6 +180,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.c
 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)wdt_hal_iram.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)hal$(DELIM)spi_slave_hal_iram.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)spi_slave_hal.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)xt_wdt_hal.c
@@ -187,8 +196,27 @@ 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)riscv$(DELIM)interrupt.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)riscv$(DELIM)interrupt_intc.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)soc$(DELIM)lldesc.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)dedic_gpio_periph.c
@@ -205,6 +233,10 @@ 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)twai_periph.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)${CHIP_SERIES}$(DELIM)uart_periph.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
@@ -223,7 +255,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)bootloader_sha.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)flash_encrypt.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
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_spiflash.c
diff --git a/arch/risc-v/src/esp32c6/hal_esp32c6.mk 
b/arch/risc-v/src/esp32c6/hal_esp32c6.mk
index 8f94d91838c..591c31c1265 100644
--- a/arch/risc-v/src/esp32c6/hal_esp32c6.mk
+++ b/arch/risc-v/src/esp32c6/hal_esp32c6.mk
@@ -44,6 +44,7 @@ INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY
 INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)include
 INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)include$(DELIM)esp_private
 INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)include$(DELIM)soc
+INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)mspi_timing_tuning$(DELIM)include
 INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)ldo$(DELIM)include
 INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)port$(DELIM)include
 INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_hw_support$(DELIM)port$(DELIM)$(CHIP_SERIES)$(DELIM)include
@@ -154,7 +155,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)$(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)systimer.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)esp_cache.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_phy$(DELIM)src$(DELIM)lib_printf.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
@@ -163,6 +166,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
@@ -193,6 +198,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.c
 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)wdt_hal_iram.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)hal$(DELIM)systimer_hal.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)rtc_io_hal.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)spi_slave_hal_iram.c
@@ -207,6 +216,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)riscv$(DELIM)interrupt.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)riscv$(DELIM)interrupt_plic.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)riscv$(DELIM)rv_utils.c
@@ -228,6 +238,19 @@ 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)timer_periph.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)twai_periph.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)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)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)lp_core$(DELIM)lp_core_i2c.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)ulp$(DELIM)lp_core$(DELIM)lp_core.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)ulp$(DELIM)lp_core$(DELIM)shared$(DELIM)ulp_lp_core_memory_shared.c
@@ -236,6 +259,10 @@ CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)ulp$
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)nuttx$(DELIM)src$(DELIM)components$(DELIM)esp_driver_gpio$(DELIM)src$(DELIM)gpio.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
@@ -254,7 +281,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)bootloader_sha.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)flash_encrypt.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
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_spiflash.c
diff --git a/arch/risc-v/src/esp32h2/hal_esp32h2.mk 
b/arch/risc-v/src/esp32h2/hal_esp32h2.mk
index 6870d1f55ca..486afe6d1d3 100644
--- a/arch/risc-v/src/esp32h2/hal_esp32h2.mk
+++ b/arch/risc-v/src/esp32h2/hal_esp32h2.mk
@@ -25,6 +25,7 @@
 INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)nuttx$(DELIM)include
 INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)nuttx$(DELIM)include$(DELIM)mbedtls
 INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)nuttx$(DELIM)$(CHIP_SERIES)$(DELIM)include
+INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)nuttx$(DELIM)src$(DELIM)components$(DELIM)esp_driver_gpio$(DELIM)include
 INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)bootloader_flash$(DELIM)include
 INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)include
 INCLUDES += 
$(INCDIR_PREFIX)$(ARCH_SRCDIR)$(DELIM)chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)private_include
@@ -136,12 +137,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_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)systimer.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)esp_cache.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_rom$(DELIM)patches$(DELIM)esp_rom_regi2c_$(CHIP_SERIES).c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_systimer.c
 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
@@ -172,6 +177,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.c
 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)wdt_hal_iram.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)hal$(DELIM)spi_slave_hal_iram.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)spi_slave_hal.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)hal$(DELIM)$(CHIP_SERIES)$(DELIM)clk_tree_hal.c
@@ -184,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)riscv$(DELIM)interrupt.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)riscv$(DELIM)interrupt_plic.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)riscv$(DELIM)rv_utils.c
@@ -204,6 +214,23 @@ 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)timer_periph.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)twai_periph.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)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)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
+
+# 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
@@ -222,7 +249,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_${CHIP_SERIES}.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)${CHIP_SERIES}$(DELIM)bootloader_soc.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)bootloader_support$(DELIM)src$(DELIM)bootloader_sha.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/risc-v/esp32c3/common/scripts/esp32c3_sections.ld 
b/boards/risc-v/esp32c3/common/scripts/esp32c3_sections.ld
index 5c632293117..a36aeb7b7b5 100644
--- a/boards/risc-v/esp32c3/common/scripts/esp32c3_sections.ld
+++ b/boards/risc-v/esp32c3/common/scripts/esp32c3_sections.ld
@@ -183,7 +183,6 @@ SECTIONS
     *libarch.a:*esp_rom_sys.*(.text .text.* .literal .literal.*)
     *libarch.a:*esp_rom_spiflash.*(.text .text.* .literal .literal.*)
     *libarch.a:*efuse_hal.*(.text .text.* .literal .literal.*)
-    *libarch.a:esp_spiflash.*(.literal .text .literal.* .text.*)
     *libarch.a:*apm_hal.*(.text .text.* .literal .literal.*)
     *libarch.a:*log.*(.text .text.* .literal .literal.*)
     *libarch.a:*log_lock.*(.literal .literal.* .text .text.*)
@@ -194,6 +193,20 @@ SECTIONS
     *libarch.a:*log_write.*(.literal.esp_log_write .text.esp_log_write)
     *libarch.a:*log_write.*(.literal.esp_log_writev .text.esp_log_writev)
     *libarch.a:*interrupt_intc.*(.literal .literal.* .text .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_utils.*(.literal .literal.* .text .text.*)
+    *libarch.a:memspi_host_driver.*(.literal .literal.* .text .text.*)
 
     *libc.a:sq_remlast.*(.literal .text .literal.* .text.*)
 
@@ -314,7 +327,19 @@ SECTIONS
     *libarch.a:*log.*(.rodata .rodata.*)
     *libarch.a:*log_noos.*(.rodata .rodata.*)
     *libarch.a:esp_spiflash.*(.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.*)
     esp_head.*(.rodata .rodata.*)
     esp_start.*(.rodata .rodata.*)
 
diff --git a/boards/risc-v/esp32c6/common/scripts/esp32c6_sections.ld 
b/boards/risc-v/esp32c6/common/scripts/esp32c6_sections.ld
index 771c7464508..577d157a93e 100644
--- a/boards/risc-v/esp32c6/common/scripts/esp32c6_sections.ld
+++ b/boards/risc-v/esp32c6/common/scripts/esp32c6_sections.ld
@@ -190,7 +190,6 @@ SECTIONS
     *libarch.a:*esp_rom_sys.*(.text .text.* .literal .literal.*)
     *libarch.a:*esp_rom_spiflash.*(.text .text.* .literal .literal.*)
     *libarch.a:*efuse_hal.*(.text .text.* .literal .literal.*)
-    *libarch.a:esp_spiflash.*(.literal .text .literal.* .text.*)
     *libarch.a:*apm_hal.*(.text .text.* .literal .literal.*)
     *libarch.a:*log.*(.text .text.* .literal .literal.*)
     *libarch.a:*log_lock.*(.literal .literal.* .text .text.*)
@@ -201,6 +200,20 @@ SECTIONS
     *libarch.a:*log_write.*(.literal.esp_log_write .text.esp_log_write)
     *libarch.a:*log_write.*(.literal.esp_log_writev .text.esp_log_writev)
     *libarch.a:*interrupt_plic.*(.literal .literal.* .text .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_utils.*(.literal .literal.* .text .text.*)
+    *libarch.a:memspi_host_driver.*(.literal .literal.* .text .text.*)
 
     *libc.a:sq_remlast.*(.literal .text .literal.* .text.*)
 
@@ -345,6 +358,19 @@ SECTIONS
     *libarch.a:*log.*(.rodata .rodata.*)
     *libarch.a:*log_noos.*(.rodata .rodata.*)
     *libarch.a:esp_spiflash.*(.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.*)
 
     esp_head.*(.rodata .rodata.*)
     esp_start.*(.rodata .rodata.*)
diff --git a/boards/risc-v/esp32c6/common/src/esp_board_spiflash.c 
b/boards/risc-v/esp32c6/common/src/esp_board_spiflash.c
index e0e021667cd..f73ef6ef3ae 100644
--- a/boards/risc-v/esp32c6/common/src/esp_board_spiflash.c
+++ b/boards/risc-v/esp32c6/common/src/esp_board_spiflash.c
@@ -473,7 +473,11 @@ int board_spiflash_init(void)
 {
   int ret = OK;
 
-  esp_spiflash_init();
+  ret = esp_spiflash_init();
+  if (ret != OK)
+    {
+      return ret;
+    }
 
 #ifdef CONFIG_ESPRESSIF_HAVE_OTA_PARTITION
   ret = init_ota_partitions();
diff --git a/boards/risc-v/esp32h2/common/scripts/esp32h2_sections.ld 
b/boards/risc-v/esp32h2/common/scripts/esp32h2_sections.ld
index 94ee5a53712..06375668a3f 100644
--- a/boards/risc-v/esp32h2/common/scripts/esp32h2_sections.ld
+++ b/boards/risc-v/esp32h2/common/scripts/esp32h2_sections.ld
@@ -198,6 +198,19 @@ SECTIONS
     *libarch.a:*log_write.*(.literal.esp_log_write .text.esp_log_write)
     *libarch.a:*log_write.*(.literal.esp_log_writev .text.esp_log_writev)
     *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.*)
     *libarch.a:*interrupt_plic.*(.literal .literal.* .text .text.*)
 
     *libc.a:sq_remlast.*(.literal .text .literal.* .text.*)
@@ -339,6 +352,19 @@ SECTIONS
     *libarch.a:*esp_efuse_utility.*(.rodata .rodata.*)
     *libarch.a:*efuse_hal.*(.rodata .rodata.*)
     *libarch.a:esp_spiflash.*(.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.*)
 
     esp_head.*(.rodata .rodata.*)
     esp_start.*(.rodata .rodata.*)

Reply via email to