From 438a52f15abd771261b98984fcfda42188d1e5be Mon Sep 17 00:00:00 2001
From: Lin Gao <lin.gao@arm.com>
Date: Fri, 29 Mar 2019 12:37:20 -0500
Subject: [PATCH] Fix handoff issue from the bootloader to the application on
 MTS_DRAGONFLY_F411RE

---
 .../COMPONENT_SPIF/SPIFBlockDevice.cpp        | 52 +++++-------------
 .../COMPONENT_SPIF/SPIFBlockDevice.h          |  6 +-
 .../blockdevice/COMPONENT_SPIF/mbed_lib.json  | 48 ++--------------
 .../device/TOOLCHAIN_ARM_STD/stm32f411re.sct  | 27 ++++++---
 .../device/TOOLCHAIN_GCC_ARM/NUCLEO_F411RE.ld | 15 +++--
 .../TOOLCHAIN_GCC_ARM/startup_STM32F41x.S     |  6 +-
 .../device/TOOLCHAIN_IAR/stm32f411xe.icf      |  9 ++-
 .../device/flash_data.h                       | 55 +++++++++++++++++++
 .../device/system_clock.c                     |  3 +-
 targets/targets.json                          | 12 ++--
 10 files changed, 124 insertions(+), 109 deletions(-)
 create mode 100644 targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/flash_data.h

diff --git a/components/storage/blockdevice/COMPONENT_SPIF/SPIFBlockDevice.cpp b/components/storage/blockdevice/COMPONENT_SPIF/SPIFBlockDevice.cpp
index c5e22d1360..b55f71707b 100644
--- a/components/storage/blockdevice/COMPONENT_SPIF/SPIFBlockDevice.cpp
+++ b/components/storage/blockdevice/COMPONENT_SPIF/SPIFBlockDevice.cpp
@@ -95,10 +95,8 @@ enum spif_default_instructions {
 // e.g. (1)Set Write Enable, (2)Program, (3)Wait Memory Ready
 SingletonPtr<PlatformMutex> SPIFBlockDevice::_mutex;
 
-#ifdef MBED_CONF_SPIF_SFDP_ENABLE
 // Local Function
 static unsigned int local_math_power(int base, int exp);
-#endif
 
 //***********************
 // SPIF Block Device APIs
@@ -130,14 +128,11 @@ int SPIFBlockDevice::init()
     uint8_t vendor_device_ids[4];
     size_t data_length = 3;
     int status = SPIF_BD_ERROR_OK;
-#ifdef MBED_CONF_SPIF_SFDP_ENABLE
     uint32_t basic_table_addr = 0;
     size_t basic_table_size = 0;
     uint32_t sector_map_table_addr = 0;
     size_t sector_map_table_size = 0;
-#endif
     spif_bd_error spi_status = SPIF_BD_ERROR_OK;
-    uint32_t density_bits = 0;
 
     _mutex->lock();
 
@@ -160,6 +155,7 @@ int SPIFBlockDevice::init()
         tr_info("INFO: Initialize flash memory OK\n");
     }
 
+
     /* Read Manufacturer ID (1byte), and Device ID (2bytes)*/
     spi_status = _spi_send_general_command(SPIF_RDID, SPI_NO_ADDRESS_COMMAND, NULL, 0, (char *)vendor_device_ids,
                                            data_length);
@@ -184,7 +180,7 @@ int SPIFBlockDevice::init()
         status = SPIF_BD_ERROR_READY_FAILED;
         goto exit_point;
     }
-    #ifdef MBED_CONF_SPIF_SFDP_ENABLE
+
     /**************************** Parse SFDP Header ***********************************/
     if (0 != _sfdp_parse_sfdp_headers(basic_table_addr, basic_table_size, sector_map_table_addr, sector_map_table_size)) {
         tr_error("ERROR: init - Parse SFDP Headers Failed");
@@ -214,22 +210,11 @@ int SPIFBlockDevice::init()
             goto exit_point;
         }
     }
-    #else
-    density_bits = MBED_CONF_SPIF_DRIVER_DENSITY_BITS;
-    _device_size_bytes = (density_bits + 1) / 8;
-    _read_instruction = SPIF_READ;
-    _prog_instruction = SPIF_PP;
-    _erase_instruction = MBED_CONF_SPIF_DRIVER_SECTOR_ERASE_INST;
-    // Set Page Size (SPI write must be done on Page limits)
-    _page_size_bytes = MBED_CONF_SPIF_DRIVER_PAGE_SIZE_BYTES;
-    //_sector_size_pages = MBED_CONF_SPIF_DRIVER_SECTOR_SIZE_PAGES;
-    _min_common_erase_size = MBED_CONF_SPIF_DRIVER_SECTOR_SIZE_PAGES * MBED_CONF_SPIF_DRIVER_PAGE_SIZE_BYTES;
+
     // Configure  BUS Mode to 1_1_1 for all commands other than Read
     // Dummy And Mode Cycles Back default 0
-    _read_dummy_and_mode_cycles = MBED_CONF_SPIF_DRIVER_READ_DUMMY_CYCLES;
-    _write_dummy_and_mode_cycles = MBED_CONF_SPIF_DRIVER_MODE_WRITE_DUMMY_CYCLES;
+    _dummy_and_mode_cycles = _write_dummy_and_mode_cycles;
     _is_initialized = true;
-    #endif
 
 exit_point:
     _mutex->unlock();
@@ -348,19 +333,17 @@ int SPIFBlockDevice::erase(bd_addr_t addr, bd_size_t in_size)
         return BD_ERROR_DEVICE_ERROR;
     }
 
+    int type = 0;
+    uint32_t offset = 0;
+    uint32_t chunk = 4096;
     int cur_erase_inst = _erase_instruction;
     int size = (int)in_size;
     bool erase_failed = false;
     int status = SPIF_BD_ERROR_OK;
-#ifdef MBED_CONF_SPIF_SFDP_ENABLE
-    int type = 0;
-    uint32_t offset = 0;
-    uint32_t chunk = 4096;
     // Find region of erased address
     int region = _utils_find_addr_region(addr);
     // Erase Types of selected region
     uint8_t bitfield = _region_erase_types_bitfield[region];
-#endif
 
     tr_info("DEBUG: erase - addr: %llu, in_size: %llu", addr, in_size);
 
@@ -376,7 +359,7 @@ int SPIFBlockDevice::erase(bd_addr_t addr, bd_size_t in_size)
 
     // For each iteration erase the largest section supported by current region
     while (size > 0) {
-#ifdef MBED_CONF_SPIF_SFDP_ENABLE
+
         // iterate to find next Largest erase type ( a. supported by region, b. smaller than size)
         // find the matching instruction and erase size chunk for that type.
         type = _utils_iterate_next_largest_erase_type(bitfield, size, (unsigned int)addr, _region_high_boundary[region]);
@@ -388,7 +371,7 @@ int SPIFBlockDevice::erase(bd_addr_t addr, bd_size_t in_size)
                  addr, size, cur_erase_inst, chunk);
         tr_debug("DEBUG: erase - Region: %d, Type:%d",
                  region, type);
-#endif
+
         _mutex->lock();
 
         if (_set_write_enable() != 0) {
@@ -399,7 +382,7 @@ int SPIFBlockDevice::erase(bd_addr_t addr, bd_size_t in_size)
         }
 
         _spi_send_erase_command(cur_erase_inst, addr, size);
-#ifdef MBED_CONF_SPIF_SFDP_ENABLE
+
         addr += chunk;
         size -= chunk;
 
@@ -408,10 +391,7 @@ int SPIFBlockDevice::erase(bd_addr_t addr, bd_size_t in_size)
             region++;
             bitfield = _region_erase_types_bitfield[region];
         }
-#else
-        addr += _min_common_erase_size;
-        size -= _min_common_erase_size;
-#endif
+
         if (false == _is_mem_ready()) {
             tr_error("ERROR: SPI After Erase Device not ready - failed\n");
             erase_failed = true;
@@ -451,7 +431,6 @@ bd_size_t SPIFBlockDevice::get_erase_size() const
 // Find minimal erase size supported by the region to which the address belongs to
 bd_size_t SPIFBlockDevice::get_erase_size(bd_addr_t addr)
 {
-#ifdef MBED_CONF_SPIF_SFDP_ENABLE
     // Find region of current address
     int region = _utils_find_addr_region(addr);
 
@@ -478,9 +457,6 @@ bd_size_t SPIFBlockDevice::get_erase_size(bd_addr_t addr)
     }
 
     return (bd_size_t)min_region_erase_size;
-#else
-    return _min_common_erase_size;
-#endif
 }
 
 bd_size_t SPIFBlockDevice::size() const
@@ -620,7 +596,6 @@ spif_bd_error SPIFBlockDevice::_spi_send_general_command(int instruction, bd_add
     return SPIF_BD_ERROR_OK;
 }
 
-#ifdef MBED_CONF_SPIF_SFDP_ENABLE
 /*********************************************************/
 /********** SFDP Parsing and Detection Functions *********/
 /*********************************************************/
@@ -912,7 +887,6 @@ int SPIFBlockDevice::_sfdp_detect_best_bus_read_mode(uint8_t *basic_param_table_
 
     return 0;
 }
-#endif
 
 int SPIFBlockDevice::_reset_flash_mem()
 {
@@ -1066,7 +1040,6 @@ int SPIFBlockDevice::_utils_iterate_next_largest_erase_type(uint8_t &bitfield, i
 /*********************************************/
 /************** Local Functions **************/
 /*********************************************/
-#ifdef MBED_CONF_SPIF_SFDP_ENABLE
 static unsigned int local_math_power(int base, int exp)
 {
     // Integer X^Y function, used to calculate size fields given in 2^N format
@@ -1077,4 +1050,5 @@ static unsigned int local_math_power(int base, int exp)
     }
     return result;
 }
-#endif
+
+
diff --git a/components/storage/blockdevice/COMPONENT_SPIF/SPIFBlockDevice.h b/components/storage/blockdevice/COMPONENT_SPIF/SPIFBlockDevice.h
index f73ae9ff30..e0e68c15e3 100644
--- a/components/storage/blockdevice/COMPONENT_SPIF/SPIFBlockDevice.h
+++ b/components/storage/blockdevice/COMPONENT_SPIF/SPIFBlockDevice.h
@@ -198,7 +198,7 @@ public:
 private:
 
     // Internal functions
-#ifdef MBED_CONF_SPIF_SFDP_ENABLE
+
     /****************************************/
     /* SFDP Detection and Parsing Functions */
     /****************************************/
@@ -222,7 +222,7 @@ private:
     int _sfdp_detect_erase_types_inst_and_size(uint8_t *basic_param_table_ptr, int basic_param_table_size,
                                                int &erase4k_inst,
                                                int *erase_type_inst_arr, unsigned int *erase_type_size_arr);
-#endif
+
     /***********************/
     /* Utilities Functions */
     /***********************/
@@ -299,8 +299,8 @@ private:
     unsigned int _read_dummy_and_mode_cycles; // Number of Dummy and Mode Bits required by Read Bus Mode
     unsigned int _write_dummy_and_mode_cycles; // Number of Dummy and Mode Bits required by Write Bus Mode
     unsigned int _dummy_and_mode_cycles; // Number of Dummy and Mode Bits required by Current Bus Mode
-    bool _is_initialized;
     uint32_t _init_ref_count;
+    bool _is_initialized;
 };
 
 #endif  /* MBED_SPIF_BLOCK_DEVICE_H */
diff --git a/components/storage/blockdevice/COMPONENT_SPIF/mbed_lib.json b/components/storage/blockdevice/COMPONENT_SPIF/mbed_lib.json
index dc3e61fdac..51b8c7eace 100644
--- a/components/storage/blockdevice/COMPONENT_SPIF/mbed_lib.json
+++ b/components/storage/blockdevice/COMPONENT_SPIF/mbed_lib.json
@@ -5,35 +5,7 @@
         "SPI_MISO": "SPI_MISO",
         "SPI_CLK":  "SPI_SCK",
         "SPI_CS":   "SPI_CS",
-        "SPI_FREQ": "40000000",
-        "SFDP_ENABLE": {
-            "help": "Enables Serial Flash Discovery Protocal for automatically determining flash parameters from the SFDP register",
-            "value": true
-        },
-        "density_bits": {
-            "help": "Flash density in bits.  16Mb = 16000000",
-            "value": null
-        },
-        "page_size_bytes": {
-            "help": "Flash page size in bytes",
-            "value": null
-        },
-        "read_dummy_cycles": {
-            "help": "Number of dummy cycles required between read cmd/addr and data output",
-            "value": null
-        },
-        "mode_write_dummy_cycles": {
-            "help": "Number of dummy cycles required between write or mode commands and data",
-            "value": null
-        },
-        "sector_erase_inst": {
-            "help": "Sector erase instruction.",
-            "value": null
-        },
-        "sector_size_pages": {
-            "help": "Sector size in pages for sector erase",
-            "value": null
-        }
+        "SPI_FREQ": "40000000"
     },
     "target_overrides": {
         "LPC54114": {
@@ -60,25 +32,25 @@
              "SPI_CLK":  "PE_12",
              "SPI_CS":   "PE_11"
         },
-         "MTB_ADV_WISE_1530": {
+        "MTB_ADV_WISE_1530": {
              "SPI_MOSI": "PC_3",
              "SPI_MISO": "PC_2",
              "SPI_CLK":  "PB_13",
              "SPI_CS":   "PC_12"
        },
-         "MTB_MXCHIP_EMW3166": {
+       "MTB_MXCHIP_EMW3166": {
              "SPI_MOSI": "PB_15",
              "SPI_MISO": "PB_14",
              "SPI_CLK":  "PB_13",
              "SPI_CS":   "PA_10"
        },
-         "MTB_USI_WM_BN_BM_22": {
+       "MTB_USI_WM_BN_BM_22": {
              "SPI_MOSI": "PC_3",
              "SPI_MISO": "PC_2",
              "SPI_CLK":  "PB_13",
              "SPI_CS":   "PA_6"
        },
-         "MTB_ADV_WISE_1570": {
+       "MTB_ADV_WISE_1570": {
              "SPI_MOSI": "PA_7",
              "SPI_MISO": "PA_6",
              "SPI_CLK":  "PA_5",
@@ -95,15 +67,7 @@
            "SPI_MOSI": "SPI3_MOSI",
            "SPI_MISO": "SPI3_MISO",
            "SPI_CLK":  "SPI3_SCK",
-           "SPI_CS":   "SPI_CS1",
-           "SPI_FREQ": "40000000",
-           "SFDP_ENABLE": null,
-           "density_bits": 16000000,
-           "page_size_bytes": 256,
-           "read_dummy_cycles":  0,
-           "mode_write_dummy_cycles": 0,
-           "sector_erase_inst": "0xD8",
-           "sector_size_pages": 256
+           "SPI_CS":   "SPI_CS1"
        }
     }
 }
diff --git a/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/TOOLCHAIN_ARM_STD/stm32f411re.sct b/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/TOOLCHAIN_ARM_STD/stm32f411re.sct
index ac2e36d4e2..eb1e29e13d 100644
--- a/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/TOOLCHAIN_ARM_STD/stm32f411re.sct
+++ b/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/TOOLCHAIN_ARM_STD/stm32f411re.sct
@@ -28,29 +28,42 @@
 ; OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;
 
+#if !defined(MBED_APP_START)
+  #define MBED_APP_START 0x08000000
+#endif
+
+#if !defined(MBED_APP_SIZE)
+  #define MBED_APP_SIZE 0x80000
+#endif
+
 #if !defined(MBED_BOOT_STACK_SIZE)
   #define MBED_BOOT_STACK_SIZE 0x400
 #endif
 
 #define Stack_Size MBED_BOOT_STACK_SIZE
 
-; STM32F411RE: 512 KB FLASH (0x80000) + 128 KB SRAM (0x20000)
-; FIRST 64 KB FLASH FOR BOOTLOADER
-; REST 448 KB FLASH FOR APPLICATION
-LR_IROM1 0x08010000 0x70000  {    ; load region size_region
+#define MBED_RAM_START              0x20000000
+#define MBED_RAM_SIZE               0x20000
+#define MBED_VECTTABLE_RAM_START    (MBED_RAM_START)
+#define MBED_VECTTABLE_RAM_SIZE     0x198
+#define MBED_RAM0_START             (MBED_RAM_START + MBED_VECTTABLE_RAM_SIZE)
+#define MBED_RAM0_SIZE              (MBED_RAM_SIZE- MBED_VECTTABLE_RAM_SIZE)
 
-  ER_IROM1 0x08010000 0x70000  {  ; load address = execution address
+; STM32F411RE: 512 KB FLASH (0x80000) + 128 KB SRAM (0x20000)
+LR_IROM1 MBED_APP_START MBED_APP_SIZE  {    ; load region size_region
+
+  ER_IROM1 MBED_APP_START MBED_APP_SIZE  {  ; load address = execution address
    *.o (RESET, +First)
    *(InRoot$$Sections)
    .ANY (+RO)
   }
 
   ; Total: 102 vectors = 408 bytes (0x198) to be reserved in RAM
-  RW_IRAM1 (0x20000000+0x198) (0x20000-0x198-Stack_Size)  {  ; RW data
+  RW_IRAM1 (MBED_RAM0_START) (MBED_RAM0_SIZE-Stack_Size)  {  ; RW data
    .ANY (+RW +ZI)
   }
 
-  ARM_LIB_STACK (0x20000000+0x20000) EMPTY -Stack_Size { ; stack
+  ARM_LIB_STACK (MBED_RAM0_START+MBED_RAM0_SIZE) EMPTY -Stack_Size { ; stack
   }
 }
 
diff --git a/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/TOOLCHAIN_GCC_ARM/NUCLEO_F411RE.ld b/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/TOOLCHAIN_GCC_ARM/NUCLEO_F411RE.ld
index 2e34f3f3d4..1a6b97a139 100644
--- a/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/TOOLCHAIN_GCC_ARM/NUCLEO_F411RE.ld
+++ b/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/TOOLCHAIN_GCC_ARM/NUCLEO_F411RE.ld
@@ -1,17 +1,24 @@
 /* Linker script for STM32F411 */
 
+#if !defined(MBED_APP_START)
+  #define MBED_APP_START 0x08000000
+#endif
+
+#if !defined(MBED_APP_SIZE)
+  #define MBED_APP_SIZE 512K
+#endif
+
 #if !defined(MBED_BOOT_STACK_SIZE)
     #define MBED_BOOT_STACK_SIZE 0x400
 #endif
 
 STACK_SIZE = MBED_BOOT_STACK_SIZE;
 
+
 /* Linker script to configure memory regions. */
 MEMORY
-{ 
-  /* First 64kB of flash reserved for bootloader */
-  /* Other 448kB for application */
-  FLASH (rx) : ORIGIN = 0x08010000, LENGTH = 448K
+{
+  FLASH (rx)   : ORIGIN = MBED_APP_START, LENGTH = MBED_APP_SIZE
 /*  CCM (rwx) : ORIGIN = 0x10000000, LENGTH = 64K */
   RAM (rwx) : ORIGIN = 0x20000198, LENGTH = 128k - 0x198
 }
diff --git a/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/TOOLCHAIN_GCC_ARM/startup_STM32F41x.S b/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/TOOLCHAIN_GCC_ARM/startup_STM32F41x.S
index b7f10ce5fc..48b4471340 100644
--- a/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/TOOLCHAIN_GCC_ARM/startup_STM32F41x.S
+++ b/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/TOOLCHAIN_GCC_ARM/startup_STM32F41x.S
@@ -66,8 +66,8 @@ __HeapLimit:
 
     .section .isr_vector
     .align 2
-    .globl __isr_vector
-__isr_vector:
+    .globl g_pfnVectors
+g_pfnVectors:
     .long    __StackTop            /* Top of Stack */
     .long    Reset_Handler         /* Reset Handler */
     .long    NMI_Handler           /* NMI Handler */
@@ -171,7 +171,7 @@ __isr_vector:
     .long     SPI4_IRQHandler                   /* SPI4 */ 
     .long     SPI5_IRQHandler                   /* SPI5 */ 
 
-    .size    __isr_vector, . - __isr_vector
+    .size    g_pfnVectors, . - g_pfnVectors
 
     .text
     .thumb
diff --git a/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/TOOLCHAIN_IAR/stm32f411xe.icf b/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/TOOLCHAIN_IAR/stm32f411xe.icf
index bf12247ac1..a69a7f8500 100644
--- a/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/TOOLCHAIN_IAR/stm32f411xe.icf
+++ b/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/TOOLCHAIN_IAR/stm32f411xe.icf
@@ -1,7 +1,10 @@
+if (!isdefinedsymbol(MBED_APP_START)) { define symbol MBED_APP_START = 0x08000000; }
+if (!isdefinedsymbol(MBED_APP_SIZE)) { define symbol MBED_APP_SIZE = 0x80000; }
+
 /* [ROM = 512kb = 0x80000] */
-define symbol __intvec_start__     = 0x08010000;
-define symbol __region_ROM_start__ = 0x08010000;
-define symbol __region_ROM_end__   = 0x0807FFFF;
+define symbol __intvec_start__     = MBED_APP_START;
+define symbol __region_ROM_start__ = MBED_APP_START;
+define symbol __region_ROM_end__   = MBED_APP_START + MBED_APP_SIZE - 1;
 
 /* [RAM = 128kb = 0x20000] Vector table dynamic copy: 102 vectors = 408 bytes (0x198) to be reserved in RAM */
 define symbol __NVIC_start__          = 0x20000000;
diff --git a/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/flash_data.h b/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/flash_data.h
new file mode 100644
index 0000000000..6324b45d77
--- /dev/null
+++ b/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/flash_data.h
@@ -0,0 +1,55 @@
+/* mbed Microcontroller Library
+ *******************************************************************************
+ * Copyright (c) 2016, STMicroelectronics
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright notice,
+ *    this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ *    this list of conditions and the following disclaimer in the documentation
+ *    and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ *    may be used to endorse or promote products derived from this software
+ *    without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *******************************************************************************
+ */
+#ifndef MBED_FLASH_DATA_H
+#define MBED_FLASH_DATA_H
+
+#include "device.h"
+#include <stdint.h>
+
+#if DEVICE_FLASH
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* FLASH SIZE */
+#define FLASH_SIZE      (uint32_t) 0x80000
+
+/* Base address of the Flash sectors Bank 1 */
+#define ADDR_FLASH_SECTOR_0     ((uint32_t)0x08000000) /* Base @ of Sector 0, 16 Kbytes */
+#define ADDR_FLASH_SECTOR_1     ((uint32_t)0x08004000) /* Base @ of Sector 1, 16 Kbytes */
+#define ADDR_FLASH_SECTOR_2     ((uint32_t)0x08008000) /* Base @ of Sector 2, 16 Kbytes */
+#define ADDR_FLASH_SECTOR_3     ((uint32_t)0x0800C000) /* Base @ of Sector 3, 16 Kbytes */
+#define ADDR_FLASH_SECTOR_4     ((uint32_t)0x08010000) /* Base @ of Sector 4, 64 Kbytes */
+#define ADDR_FLASH_SECTOR_5     ((uint32_t)0x08020000) /* Base @ of Sector 5, 128 Kbytes */
+#define ADDR_FLASH_SECTOR_6     ((uint32_t)0x08040000) /* Base @ of Sector 6, 128 Kbytes */
+#define ADDR_FLASH_SECTOR_7     ((uint32_t)0x08060000) /* Base @ of Sector 7, 128 Kbytes */
+
+#endif
+#endif
diff --git a/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/system_clock.c b/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/system_clock.c
index 6ae08aac48..e7cc6eed4e 100644
--- a/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/system_clock.c
+++ b/targets/TARGET_STM/TARGET_STM32F4/TARGET_MTS_DRAGONFLY_F411RE/device/system_clock.c
@@ -36,6 +36,7 @@
 
 #include "stm32f4xx.h"
 #include "mbed_debug.h"
+#include "nvic_addr.h"
 
 /*!< Uncomment the following line if you need to relocate your vector Table in
      Internal SRAM. */
@@ -96,7 +97,7 @@ void SystemInit(void)
 #ifdef VECT_TAB_SRAM
     SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
 #else
-    SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
+    SCB->VTOR = NVIC_FLASH_VECTOR_ADDRESS;   /* Vector Table Relocation in Internal FLASH */
 #endif
 
 }
diff --git a/targets/targets.json b/targets/targets.json
index df184eb9d3..6f394f9448 100644
--- a/targets/targets.json
+++ b/targets/targets.json
@@ -4301,6 +4301,7 @@
         "inherits": ["FAMILY_STM32"],
         "core": "Cortex-M4F",
         "extra_labels_add": ["STM32F4", "STM32F411RE"],
+        "components_add": ["FLASHIAP"],
         "config": {
             "modem_is_on_board": {
                 "help": "Value: Tells the build system that the modem is on-board as oppose to a plug-in shield/module.",
@@ -4314,17 +4315,14 @@
             }
         },
         "overrides": { "lse_available": 0 },
-        "macros_add": ["HSE_VALUE=26000000", "VECT_TAB_OFFSET=0x08010000"],
-        "post_binary_hook": {
-            "function": "MTSCode.combine_bins_mts_dragonfly",
-            "toolchains": ["GCC_ARM", "ARM_STD", "ARM_MICRO", "IAR"]
-        },
-        "device_has_add": ["MPU"],
+        "macros_add": ["HSE_VALUE=26000000"],
+        "device_has_add": ["MPU", "FLASH"],
         "device_has_remove": [
             "SERIAL_FC"
         ],
         "release_versions": ["2", "5"],
-        "device_name": "STM32F411RE"
+        "device_name": "STM32F411RE",
+        "bootloader_supported": true
     },
     "MTS_DRAGONFLY_L471QG": {
         "inherits": ["FAMILY_STM32"],