diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Include/stm32f745xx.h b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Include/stm32f745xx.h index 1ad067ea47..67488dd607 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Include/stm32f745xx.h +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Include/stm32f745xx.h @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f745xx.h * @author MCD Application Team - * @version V1.1.0 - * @date 22-April-2016 + * @version V1.1.2 + * @date 23-September-2016 * @brief CMSIS Cortex-M7 Device Peripheral Access Layer Header File. * * This file contains: @@ -312,7 +312,6 @@ typedef struct __IO uint32_t IER; /*!< CEC interrupt enable register, Address offset:0x14 */ }CEC_TypeDef; - /** * @brief CRC calculation unit */ @@ -405,7 +404,6 @@ typedef struct __IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */ } DMA_TypeDef; - /** * @brief DMA2D Controller */ @@ -601,7 +599,7 @@ typedef struct __IO uint32_t PUPDR; /*!< GPIO port pull-up/pull-down register, Address offset: 0x0C */ __IO uint32_t IDR; /*!< GPIO port input data register, Address offset: 0x10 */ __IO uint32_t ODR; /*!< GPIO port output data register, Address offset: 0x14 */ - __IO uint32_t BSRR; /*!< GPIO port bit set/reset low register, Address offset: 0x18 */ + __IO uint32_t BSRR; /*!< GPIO port bit set/reset register, Address offset: 0x18 */ __IO uint32_t LCKR; /*!< GPIO port configuration lock register, Address offset: 0x1C */ __IO uint32_t AFR[2]; /*!< GPIO alternate function registers, Address offset: 0x20-0x24 */ } GPIO_TypeDef; @@ -805,7 +803,6 @@ typedef struct __IO uint32_t DIR; /*!< Debug Information register, Address offset: 0x18 */ } SPDIFRX_TypeDef; - /** * @brief SD host Interface */ @@ -1270,7 +1267,7 @@ typedef struct #define IWDG ((IWDG_TypeDef *) IWDG_BASE) #define SPI2 ((SPI_TypeDef *) SPI2_BASE) #define SPI3 ((SPI_TypeDef *) SPI3_BASE) -#define SPDIFRX ((SPDIFRX_TypeDef *) SPDIFRX_BASE) +#define SPDIFRX ((SPDIFRX_TypeDef *) SPDIFRX_BASE) #define USART2 ((USART_TypeDef *) USART2_BASE) #define USART3 ((USART_TypeDef *) USART3_BASE) #define UART4 ((USART_TypeDef *) UART4_BASE) @@ -3612,7 +3609,6 @@ typedef struct /******************** Bit definition for DMA2D_BGCLUT register **************/ - /******************************************************************************/ /* */ /* External Interrupt/Event Controller */ @@ -3922,6 +3918,7 @@ typedef struct #define FLASH_OPTCR1_BOOT_ADD0 0x0000FFFFU #define FLASH_OPTCR1_BOOT_ADD1 0xFFFF0000U + /******************************************************************************/ /* */ /* Flexible Memory Controller */ @@ -5836,7 +5833,7 @@ typedef struct #define RTC_CR_OSEL_1 0x00400000U #define RTC_CR_POL 0x00100000U #define RTC_CR_COSEL 0x00080000U -#define RTC_CR_BCK 0x00040000U +#define RTC_CR_BKP 0x00040000U #define RTC_CR_SUB1H 0x00020000U #define RTC_CR_ADD1H 0x00010000U #define RTC_CR_TSIE 0x00008000U @@ -5856,6 +5853,9 @@ typedef struct #define RTC_CR_WUCKSEL_1 0x00000002U #define RTC_CR_WUCKSEL_2 0x00000004U +/* Legacy define */ +#define RTC_CR_BCK RTC_CR_BKP + /******************** Bits definition for RTC_ISR register ******************/ #define RTC_ISR_ITSF 0x00020000U #define RTC_ISR_RECALPF 0x00010000U @@ -6431,7 +6431,6 @@ typedef struct #define SPDIFRX_DIR_THI 0x000013FFU /*! - - - - - - - -Release Notes for STM32F7xx CMSIS - - -
-


-

-
- - - - - - -
- - - - - - - - - -
Back to Release page
-

Release -Notes for STM32F7xx CMSIS

-

Copyright -2016 STMicroelectronics

-

-
-

 

- - - - - - -
- -

Update History

-

V1.1.0 -/ 22-April-2016

Main -Changes

-
  • Add the support of STM32F765xx, STM32F767xx, STM32F768xx, STM32F769xx, STM32F777xx, STM32F778xx and STM32F779xx devices
    • Add "stm32f765xx.h", "stm32f767xx.h", "stm32f769xx.h", "stm32f777xx.h" and "stm32f779xx.h" header files
    • Add startup files "startup_stm32f765xx.s", "startup_stm32f767xx.s", "startup_stm32f769xx.s", "startup_stm32f777xx.s" and "startup_stm32f779xx.s" for EWARM, MDK-ARM and SW4STM32 toolchains
    • Add Linker files "stm32f765xx_flash.icf", "stm32f765xx_sram.icf" and "stm32f765xx_ITCM_flash.icf" used within EWARM Workspaces
    • Add Linker files "stm32f767xx_flash.icf", "stm32f767xx_sram.icf" and "stm32f767xx_ITCM_flash.icf" used within EWARM Workspaces
    • Add Linker files "stm32f769xx_flash.icf", "stm32f769xx_sram.icf" and "stm32f769xx_ITCM_flash.icf" used within EWARM Workspaces
    • Add Linker files "stm32f777xx_flash.icf", "stm32f777xx_sram.icf" and "stm32f777xx_ITCM_flash.icf" used within EWARM Workspaces
    • Add Linker files "stm32f779xx_flash.icf", "stm32f779xx_sram.icf" and "stm32f779xx_ITCM_flash.icf" used within EWARM Workspaces
    • STM32F768xx cmsis files are associated with STM32F767xx ones, as there is no difference between these devices on HAL side
    • STM32F778xx cmsis files are associated with STM32F777xx ones, as there is no difference between these devices on HAL side
  • All devices header files
    • Update Bit Definition names in DCMI_RISR / DCMI_IER registers
    • Update Bit Definition names in DMA2D_CR / DMA2D_FGPFCCR / DMA2D_BGPFCCR / DMA2D_OPFCCR registers
    • Update QUADSPI_CR_FTHRES Bit Definition in QUADSPI_CR register
    • Rename SAI_xFRCR_FSPO to SAI_xFRCR_FSPOL in SAI_xFRCR register
    • Rename ADC_CSR_DOVRx Bit Definition to ADC_CSR_OVRx in ADC_CSR register
    • Rename LTDC_GCR_DTEN Bit Definition to LTDC_GCR_DEN in LTDC_GCR register
    • Rename PWR_CSR1_UDSWRDY Bit Definition to PWR_CSR1_UDRDY in PWR_CSR1 register
    • Rename RTC_TAMPCR_TAMPx_TRG Bit Definition to RTC_TAMPCR_TAMPxTRG in RTC_TAMPCR register
    • Rename USART_ISR_LBD Bit Definition to USART_ISR_LBDF in USART_ISR register
    • Rename IS_SAI_BLOCK_PERIPH macro to IS_SAI_ALL_INSTANCE
    • Rename DCMI_ICR_OVF_ISC Bit Definition to DCMI_ICR_OVR_ISC
    • Rename DMA2D_IFSR register to DMA2D_IFCR
    • Rename EXTI_IMR_MRx Bit Definition to EXTI_IMR_IM0x
    • Rename EXTI_EMR_MRx Bit Definition to EXTI_EMR_EMx
    • Fix LPTIM_CR_SNGSTRT Bit Definition value in LPTIM_CR register
    • Fix mask incorrect naming in DBGMCU_APB2_FZ register
    • Fix Bits Definition for SYSCFG_EXTICR4_EXTI13_PI and SYSCFG_EXTICR4_EXTI13_PJ
    • Add DAC_CR_DMAUDRIEx Bit Definition in DAC_CR register
    • Add a new mask EXTI_IMR_IM in EXTI bits definition: Interrupt Mask All
    • Add UID_BASE define for Unique ID register base address
    • Add FLASHSIZE_BASE define for register base address
    • Add PACKAGESIZE_BASE define for register base address
    • Add FLASH_SECTOR_TOTAL define for total Flash sector number
    • Add Bits Definition for DCMI_ESCR, DCMI_ESUR, DCMI_CWSTRT, DCMI_CWSIZE and DCMI_DR registers
    • Add PWR_CSR1_EIWUP Bit Definition in PWR_CSR1 register
    • Add IP version define for QSPI: QSPI_V1_0
    • Add IS_UART_DRIVER_ENABLE_INSTANCE macro
    • Apply an 'U' suffix to all constants of 'unsigned' type (MISRA-C 2004 rule 10.6)
    • Remove uint32_t cast in all defines
    • Remove DMA_SxCR_ACK Bit Definition in DMA_SxCR register
    • Remove I2C_CR1_SWRST / I2C_CR1_WUPEN Bit Definitions in I2C_CR1 register
    • Keep the same DCMI register names (RISR, MISR, CWSTRTR and CWSIZER) as F4 family
  • system_stm32f7xx.c/.h files
    • Remove external memories configuration from the system_stm32f7xx.c common file (moved to Template Projects)
    • Add declaration of AHBPrescTable / APBPrescTable constant tables
  • stm32f7xx.h
    • Rename __STM32F7xx_CMSIS_DEVICE_VERSION_xx defines to __STM32F7_CMSIS_VERSION_xx (MISRA-C 2004 rule 5.1)

V1.0.3 -/ 13-November-2015

-

Main -Changes

-
  • stm32f745xx.h, stm32f746xx.h and stm32f756xx.h files
    • update __CM7_REV with proper Cortex M7 core revision
    • update SAI_xCR2_CPL bit definition
    • update WWDG bits naming to be aligned with reference manual
    • rename I2C_CR1_DFN bit to I2C_CR1_DNF
    • remove OR register definition from LPTIM_TypeDef structure
  • system_stm32f7xx.c
    • update SystemInit_ExtMemCtl() function implementation to allow simultaneous use of SDRAM and SRAM external memories

V1.0.2 -/ 21-September-2015

-

Main -Changes

-
  • stm32f745xx.h, stm32f746xx.h and stm32f756xx.h files
    • add new define USB_OTG_DOEPMSK_OTEPSPRM
    • add new define USB_OTG_DOEPINT_OTEPSPR

V1.0.1 -/ 25-June-2015

-

Main -Changes

-
  • stm32f745xx.h, stm32f746xx.h and stm32f756xx.h files
    • update IDR field declaration in CRC_TypeDef sructure
    • add I2C Own address 2 mask bits defininition in the I2C_OAR2 register
    • update SAI_xSR_FLVL_2 bit definition
  • stm32f756xx.h file
    • rename HASH_STR_NBWx bits definition to HASH_STR_NBLWx
    • rename HASH_IMR_DINIM bit definition to HASH_IMR_DINIE
    • rename HASH_IMR_DCIM bit definition to HASH_IMR_DCIE

V1.0.0 -/ 28-April-2015

-

Main -Changes

-
  • First -official release for STM32F756xx/746xx/745xx -devices
-
    -
-

License

-

-
-
-
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. -
  3. 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.
  4. -
  5. Neither the -name of STMicroelectronics nor the names of its contributors may be -used to endorse or promote products derived
    -
  6. -
-       -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.
-
-
-

  

- -
-
-

For -complete documentation on STM32 Microcontrollers -visit www.st.com/STM32

-
-

-
-
-

 

-
+ + + + + + + +Release Notes for STM32F7xx CMSIS + + +
+


+

+
+ + + + + + +
+ + + + + + + + + +
Back to Release page
+

Release +Notes for STM32F7xx CMSIS

+

Copyright +2016 STMicroelectronics

+

+
+

 

+ + + + + + +
+ +

Update History

+

V1.1.2 +/ 23-September-2016

Main +Changes

+
  • All devices header files
    • Rename RTC_CR_BCK Bit Definition to RTC_CR_BKP in RTC_CR register

V1.1.1 +/ 01-July-2016

Main +Changes

+
  • stm32f7xx.h
    • update to respectively associate STM32F778xx and STM32F768xx devices to STM32F779xx and STM32F769xx devices

V1.1.0 +/ 22-April-2016

Main +Changes

+
  • Add the support of STM32F765xx, STM32F767xx, STM32F768xx, STM32F769xx, STM32F777xx, STM32F778xx and STM32F779xx devices
    • Add "stm32f765xx.h", "stm32f767xx.h", "stm32f769xx.h", "stm32f777xx.h" and "stm32f779xx.h" header files
    • Add startup files "startup_stm32f765xx.s", "startup_stm32f767xx.s", "startup_stm32f769xx.s", "startup_stm32f777xx.s" and "startup_stm32f779xx.s" for EWARM, MDK-ARM and SW4STM32 toolchains
    • Add Linker files "stm32f765xx_flash.icf", "stm32f765xx_sram.icf" and "stm32f765xx_ITCM_flash.icf" used within EWARM Workspaces
    • Add Linker files "stm32f767xx_flash.icf", "stm32f767xx_sram.icf" and "stm32f767xx_ITCM_flash.icf" used within EWARM Workspaces
    • Add Linker files "stm32f769xx_flash.icf", "stm32f769xx_sram.icf" and "stm32f769xx_ITCM_flash.icf" used within EWARM Workspaces
    • Add Linker files "stm32f777xx_flash.icf", "stm32f777xx_sram.icf" and "stm32f777xx_ITCM_flash.icf" used within EWARM Workspaces
    • Add Linker files "stm32f779xx_flash.icf", "stm32f779xx_sram.icf" and "stm32f779xx_ITCM_flash.icf" used within EWARM Workspaces
    • STM32F768xx cmsis files are associated with STM32F767xx ones, as there is no difference between these devices on HAL side
    • STM32F778xx cmsis files are associated with STM32F777xx ones, as there is no difference between these devices on HAL side
  • All devices header files
    • Update Bit Definition names in DCMI_RISR / DCMI_IER registers
    • Update Bit Definition names in DMA2D_CR / DMA2D_FGPFCCR / DMA2D_BGPFCCR / DMA2D_OPFCCR registers
    • Update QUADSPI_CR_FTHRES Bit Definition in QUADSPI_CR register
    • Rename SAI_xFRCR_FSPO to SAI_xFRCR_FSPOL in SAI_xFRCR register
    • Rename ADC_CSR_DOVRx Bit Definition to ADC_CSR_OVRx in ADC_CSR register
    • Rename LTDC_GCR_DTEN Bit Definition to LTDC_GCR_DEN in LTDC_GCR register
    • Rename PWR_CSR1_UDSWRDY Bit Definition to PWR_CSR1_UDRDY in PWR_CSR1 register
    • Rename RTC_TAMPCR_TAMPx_TRG Bit Definition to RTC_TAMPCR_TAMPxTRG in RTC_TAMPCR register
    • Rename USART_ISR_LBD Bit Definition to USART_ISR_LBDF in USART_ISR register
    • Rename IS_SAI_BLOCK_PERIPH macro to IS_SAI_ALL_INSTANCE
    • Rename DCMI_ICR_OVF_ISC Bit Definition to DCMI_ICR_OVR_ISC
    • Rename DMA2D_IFSR register to DMA2D_IFCR
    • Rename EXTI_IMR_MRx Bit Definition to EXTI_IMR_IM0x
    • Rename EXTI_EMR_MRx Bit Definition to EXTI_EMR_EMx
    • Fix LPTIM_CR_SNGSTRT Bit Definition value in LPTIM_CR register
    • Fix mask incorrect naming in DBGMCU_APB2_FZ register
    • Fix Bits Definition for SYSCFG_EXTICR4_EXTI13_PI and SYSCFG_EXTICR4_EXTI13_PJ
    • Add DAC_CR_DMAUDRIEx Bit Definition in DAC_CR register
    • Add a new mask EXTI_IMR_IM in EXTI bits definition: Interrupt Mask All
    • Add UID_BASE define for Unique ID register base address
    • Add FLASHSIZE_BASE define for register base address
    • Add PACKAGESIZE_BASE define for register base address
    • Add FLASH_SECTOR_TOTAL define for total Flash sector number
    • Add Bits Definition for DCMI_ESCR, DCMI_ESUR, DCMI_CWSTRT, DCMI_CWSIZE and DCMI_DR registers
    • Add PWR_CSR1_EIWUP Bit Definition in PWR_CSR1 register
    • Add IP version define for QSPI: QSPI_V1_0
    • Add IS_UART_DRIVER_ENABLE_INSTANCE macro
    • Apply an 'U' suffix to all constants of 'unsigned' type (MISRA-C 2004 rule 10.6)
    • Remove uint32_t cast in all defines
    • Remove DMA_SxCR_ACK Bit Definition in DMA_SxCR register
    • Remove I2C_CR1_SWRST / I2C_CR1_WUPEN Bit Definitions in I2C_CR1 register
    • Keep the same DCMI register names (RISR, MISR, CWSTRTR and CWSIZER) as F4 family
  • system_stm32f7xx.c/.h files
    • Remove external memories configuration from the system_stm32f7xx.c common file (moved to Template Projects)
    • Add declaration of AHBPrescTable / APBPrescTable constant tables
  • stm32f7xx.h
    • Rename __STM32F7xx_CMSIS_DEVICE_VERSION_xx defines to __STM32F7_CMSIS_VERSION_xx (MISRA-C 2004 rule 5.1)

V1.0.3 +/ 13-November-2015

+

Main +Changes

+
  • stm32f745xx.h, stm32f746xx.h and stm32f756xx.h files
    • update __CM7_REV with proper Cortex M7 core revision
    • update SAI_xCR2_CPL bit definition
    • update WWDG bits naming to be aligned with reference manual
    • rename I2C_CR1_DFN bit to I2C_CR1_DNF
    • remove OR register definition from LPTIM_TypeDef structure
  • system_stm32f7xx.c
    • update SystemInit_ExtMemCtl() function implementation to allow simultaneous use of SDRAM and SRAM external memories

V1.0.2 +/ 21-September-2015

+

Main +Changes

+
  • stm32f745xx.h, stm32f746xx.h and stm32f756xx.h files
    • add new define USB_OTG_DOEPMSK_OTEPSPRM
    • add new define USB_OTG_DOEPINT_OTEPSPR

V1.0.1 +/ 25-June-2015

+

Main +Changes

+
  • stm32f745xx.h, stm32f746xx.h and stm32f756xx.h files
    • update IDR field declaration in CRC_TypeDef sructure
    • add I2C Own address 2 mask bits defininition in the I2C_OAR2 register
    • update SAI_xSR_FLVL_2 bit definition
  • stm32f756xx.h file
    • rename HASH_STR_NBWx bits definition to HASH_STR_NBLWx
    • rename HASH_IMR_DINIM bit definition to HASH_IMR_DINIE
    • rename HASH_IMR_DCIM bit definition to HASH_IMR_DCIE

V1.0.0 +/ 28-April-2015

+

Main +Changes

+
  • First +official release for STM32F756xx/746xx/745xx +devices
+
    +
+

License

+

+
+
+
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. +
  3. 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.
  4. +
  5. Neither the +name of STMicroelectronics nor the names of its contributors may be +used to endorse or promote products derived
    +
  6. +
+       +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.
+
+
+

  

+ +
+
+

For +complete documentation on STM32 Microcontrollers +visit www.st.com/STM32

+
+

+
+
+

 

+
\ No newline at end of file diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f745xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f745xx.s index 3ebeec7603..6e60e61420 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f745xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f745xx.s @@ -1,8 +1,8 @@ ;******************** (C) COPYRIGHT 2016 STMicroelectronics ******************** ;* File Name : startup_stm32f745xx.s ;* Author : MCD Application Team -;* Version : V1.1.0 -;* Date : 22-April-2016 +;* Version : V1.1.2 +;* Date : 23-September-2016 ;* Description : STM32F745xx devices vector table for MDK-ARM toolchain. ;* This module performs: ;* - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f746xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f746xx.s index 90bacb62ba..0873a994ea 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f746xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f746xx.s @@ -1,8 +1,8 @@ ;******************** (C) COPYRIGHT 2016 STMicroelectronics ******************** ;* File Name : startup_stm32f746xx.s ;* Author : MCD Application Team -;* Version : V1.1.0 -;* Date : 22-April-2016 +;* Version : V1.1.2 +;* Date : 23-September-2016 ;* Description : STM32F746xx devices vector table for MDK-ARM toolchain. ;* This module performs: ;* - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f756xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f756xx.s index fcdeba4022..fbe01a9c74 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f756xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f756xx.s @@ -1,8 +1,8 @@ ;******************** (C) COPYRIGHT 2016 STMicroelectronics ******************** ;* File Name : startup_stm32f756xx.s ;* Author : MCD Application Team -;* Version : V1.1.0 -;* Date : 22-April-2016 +;* Version : V1.1.2 +;* Date : 23-September-2016 ;* Description : STM32F756xx devices vector table for MDK-ARM toolchain. ;* This module performs: ;* - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f765xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f765xx.s index db2383698e..ce9ab8b0ee 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f765xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f765xx.s @@ -1,8 +1,8 @@ ;******************** (C) COPYRIGHT 2016 STMicroelectronics ******************** ;* File Name : startup_stm32f765xx.s ;* Author : MCD Application Team -;* Version : V1.1.0 -;* Date : 22-April-2016 +;* Version : V1.1.2 +;* Date : 23-September-2016 ;* Description : STM32F765xx devices vector table for MDK-ARM toolchain. ;* This module performs: ;* - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f767xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f767xx.s index 0f452c125e..1290fc3058 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f767xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f767xx.s @@ -1,8 +1,8 @@ ;******************** (C) COPYRIGHT 2016 STMicroelectronics ******************** ;* File Name : startup_stm32f767xx.s ;* Author : MCD Application Team -;* Version : V1.1.0 -;* Date : 22-April-2016 +;* Version : V1.1.2 +;* Date : 23-September-2016 ;* Description : STM32F767xx devices vector table for MDK-ARM toolchain. ;* This module performs: ;* - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f769xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f769xx.s index bc0ec1b395..0168c51d38 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f769xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f769xx.s @@ -1,8 +1,8 @@ ;******************** (C) COPYRIGHT 2016 STMicroelectronics ******************** ;* File Name : startup_stm32f769xx.s ;* Author : MCD Application Team -;* Version : V1.1.0 -;* Date : 22-April-2016 +;* Version : V1.1.2 +;* Date : 23-September-2016 ;* Description : STM32F769xx devices vector table for MDK-ARM toolchain. ;* This module performs: ;* - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f777xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f777xx.s index fb211c8e8f..dd76df44c5 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f777xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f777xx.s @@ -1,8 +1,8 @@ ;******************** (C) COPYRIGHT 2016 STMicroelectronics ******************** ;* File Name : startup_stm32f777xx.s ;* Author : MCD Application Team -;* Version : V1.1.0 -;* Date : 22-April-2016 +;* Version : V1.1.2 +;* Date : 23-September-2016 ;* Description : STM32F777xx devices vector table for MDK-ARM toolchain. ;* This module performs: ;* - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f779xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f779xx.s index 23bf8b3eec..b56372152d 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f779xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/arm/startup_stm32f779xx.s @@ -1,8 +1,8 @@ ;******************** (C) COPYRIGHT 2016 STMicroelectronics ******************** ;* File Name : startup_stm32f779xx.s ;* Author : MCD Application Team -;* Version : V1.1.0 -;* Date : 22-April-2016 +;* Version : V1.1.2 +;* Date : 23-September-2016 ;* Description : STM32F779xx devices vector table for MDK-ARM toolchain. ;* This module performs: ;* - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f745xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f745xx.s index 5b9a54653c..e9c8d7f67c 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f745xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f745xx.s @@ -2,8 +2,8 @@ ****************************************************************************** * @file startup_stm32f745xx.s * @author MCD Application Team - * @version V1.1.0 - * @date 22-April-2016 + * @version V1.1.2 + * @date 23-September-2016 * @brief STM32F745xx Devices vector table for GCC toolchain based application. * This module performs: * - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f746xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f746xx.s index 4cfde098a6..91a15dd44f 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f746xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f746xx.s @@ -2,8 +2,8 @@ ****************************************************************************** * @file startup_stm32f746xx.s * @author MCD Application Team - * @version V1.1.0 - * @date 22-April-2016 + * @version V1.1.2 + * @date 23-September-2016 * @brief STM32F746xx Devices vector table for GCC based toolchain. * This module performs: * - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f756xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f756xx.s index ed6bb646c5..dbbcf749b3 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f756xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f756xx.s @@ -2,8 +2,8 @@ ****************************************************************************** * @file startup_stm32f756xx.s * @author MCD Application Team - * @version V1.1.0 - * @date 22-April-2016 + * @version V1.1.2 + * @date 23-September-2016 * @brief STM32F756xx Devices vector table for GCC based toolchain. * This module performs: * - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f765xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f765xx.s index 8f6bf7d609..df1bf49d60 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f765xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f765xx.s @@ -2,8 +2,8 @@ ****************************************************************************** * @file startup_stm32f765xx.s * @author MCD Application Team - * @version V1.1.0 - * @date 22-April-2016 + * @version V1.1.2 + * @date 23-September-2016 * @brief STM32F765xx Devices vector table for GCC based toolchain. * This module performs: * - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f767xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f767xx.s index 12adc775d3..b277904c19 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f767xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f767xx.s @@ -2,8 +2,8 @@ ****************************************************************************** * @file startup_stm32f767xx.s * @author MCD Application Team - * @version V1.1.0 - * @date 22-April-2016 + * @version V1.1.2 + * @date 23-September-2016 * @brief STM32F767xx Devices vector table for GCC based toolchain. * This module performs: * - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f769xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f769xx.s index 4d7c3e3ffb..1e4b87727b 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f769xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f769xx.s @@ -2,8 +2,8 @@ ****************************************************************************** * @file startup_stm32f769xx.s * @author MCD Application Team - * @version V1.1.0 - * @date 22-April-2016 + * @version V1.1.2 + * @date 23-September-2016 * @brief STM32F769xx Devices vector table for GCC based toolchain. * This module performs: * - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f777xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f777xx.s index 0094d3a263..530f263cf3 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f777xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f777xx.s @@ -2,8 +2,8 @@ ****************************************************************************** * @file startup_stm32f777xx.s * @author MCD Application Team - * @version V1.1.0 - * @date 22-April-2016 + * @version V1.1.2 + * @date 23-September-2016 * @brief STM32F777xx Devices vector table for GCC based toolchain. * This module performs: * - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f779xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f779xx.s index d5fc055772..9e1fdb3781 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f779xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/gcc/startup_stm32f779xx.s @@ -2,8 +2,8 @@ ****************************************************************************** * @file startup_stm32f779xx.s * @author MCD Application Team - * @version V1.1.0 - * @date 22-April-2016 + * @version V1.1.2 + * @date 23-September-2016 * @brief STM32F779xx Devices vector table for GCC based toolchain. * This module performs: * - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f745xx_ITCM_flash.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f745xx_ITCM_flash.icf index 03ae74b9cd..7dfaf768a2 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f745xx_ITCM_flash.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f745xx_ITCM_flash.icf @@ -1,34 +1,35 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x00200000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x00200000; -define symbol __ICFEDIT_region_ROM_end__ = 0x002FFFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2004FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, - block CSTACK, block HEAP }; \ No newline at end of file +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x00200000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x00200000; +define symbol __ICFEDIT_region_ROM_end__ = 0x002FFFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2004FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, + block CSTACK, block HEAP }; +place in ITCMRAM_region { }; \ No newline at end of file diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f745xx_flash.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f745xx_flash.icf index 663a68fd1b..a321e0e888 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f745xx_flash.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f745xx_flash.icf @@ -1,34 +1,34 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x08000000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x08000000; -define symbol __ICFEDIT_region_ROM_end__ = 0x080FFFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2004FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x08000000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x08000000; +define symbol __ICFEDIT_region_ROM_end__ = 0x080FFFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2004FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, block CSTACK, block HEAP }; \ No newline at end of file diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f745xx_sram.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f745xx_sram.icf index d55c0c25d4..3e3947d8b6 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f745xx_sram.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f745xx_sram.icf @@ -1,34 +1,34 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x20000000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x20000000; -define symbol __ICFEDIT_region_ROM_end__ = 0x2002FFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20030000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2004FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, - block CSTACK, block HEAP }; +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x20000000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x20000000; +define symbol __ICFEDIT_region_ROM_end__ = 0x2002FFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20030000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2004FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, + block CSTACK, block HEAP }; diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f746xx_ITCM_flash.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f746xx_ITCM_flash.icf index 03ae74b9cd..7dfaf768a2 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f746xx_ITCM_flash.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f746xx_ITCM_flash.icf @@ -1,34 +1,35 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x00200000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x00200000; -define symbol __ICFEDIT_region_ROM_end__ = 0x002FFFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2004FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, - block CSTACK, block HEAP }; \ No newline at end of file +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x00200000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x00200000; +define symbol __ICFEDIT_region_ROM_end__ = 0x002FFFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2004FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, + block CSTACK, block HEAP }; +place in ITCMRAM_region { }; \ No newline at end of file diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f746xx_flash.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f746xx_flash.icf index 663a68fd1b..a321e0e888 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f746xx_flash.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f746xx_flash.icf @@ -1,34 +1,34 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x08000000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x08000000; -define symbol __ICFEDIT_region_ROM_end__ = 0x080FFFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2004FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x08000000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x08000000; +define symbol __ICFEDIT_region_ROM_end__ = 0x080FFFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2004FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, block CSTACK, block HEAP }; \ No newline at end of file diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f746xx_sram.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f746xx_sram.icf index d55c0c25d4..3e3947d8b6 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f746xx_sram.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f746xx_sram.icf @@ -1,34 +1,34 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x20000000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x20000000; -define symbol __ICFEDIT_region_ROM_end__ = 0x2002FFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20030000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2004FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, - block CSTACK, block HEAP }; +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x20000000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x20000000; +define symbol __ICFEDIT_region_ROM_end__ = 0x2002FFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20030000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2004FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, + block CSTACK, block HEAP }; diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f756xx_ITCM_flash.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f756xx_ITCM_flash.icf index 03ae74b9cd..7dfaf768a2 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f756xx_ITCM_flash.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f756xx_ITCM_flash.icf @@ -1,34 +1,35 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x00200000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x00200000; -define symbol __ICFEDIT_region_ROM_end__ = 0x002FFFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2004FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, - block CSTACK, block HEAP }; \ No newline at end of file +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x00200000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x00200000; +define symbol __ICFEDIT_region_ROM_end__ = 0x002FFFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2004FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, + block CSTACK, block HEAP }; +place in ITCMRAM_region { }; \ No newline at end of file diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f756xx_flash.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f756xx_flash.icf index 663a68fd1b..a321e0e888 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f756xx_flash.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f756xx_flash.icf @@ -1,34 +1,34 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x08000000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x08000000; -define symbol __ICFEDIT_region_ROM_end__ = 0x080FFFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2004FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x08000000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x08000000; +define symbol __ICFEDIT_region_ROM_end__ = 0x080FFFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2004FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, block CSTACK, block HEAP }; \ No newline at end of file diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f756xx_sram.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f756xx_sram.icf index d55c0c25d4..3e3947d8b6 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f756xx_sram.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f756xx_sram.icf @@ -1,34 +1,34 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x20000000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x20000000; -define symbol __ICFEDIT_region_ROM_end__ = 0x2002FFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20030000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2004FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, - block CSTACK, block HEAP }; +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x20000000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x20000000; +define symbol __ICFEDIT_region_ROM_end__ = 0x2002FFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20030000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2004FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, + block CSTACK, block HEAP }; diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f765xx_ITCM_flash.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f765xx_ITCM_flash.icf index afa86bfdf4..8d3b21a1c3 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f765xx_ITCM_flash.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f765xx_ITCM_flash.icf @@ -1,34 +1,35 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x00200000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x00200000; -define symbol __ICFEDIT_region_ROM_end__ = 0x003FFFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, - block CSTACK, block HEAP }; \ No newline at end of file +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x00200000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x00200000; +define symbol __ICFEDIT_region_ROM_end__ = 0x003FFFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, + block CSTACK, block HEAP }; +place in ITCMRAM_region { }; \ No newline at end of file diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f765xx_flash.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f765xx_flash.icf index d519df8549..ceb5a7b0c5 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f765xx_flash.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f765xx_flash.icf @@ -1,34 +1,34 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x08000000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x08000000; -define symbol __ICFEDIT_region_ROM_end__ = 0x081FFFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x08000000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x08000000; +define symbol __ICFEDIT_region_ROM_end__ = 0x081FFFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, block CSTACK, block HEAP }; \ No newline at end of file diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f765xx_sram.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f765xx_sram.icf index f3db1bb369..ea05b7fae4 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f765xx_sram.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f765xx_sram.icf @@ -1,34 +1,34 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x20000000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x20000000; -define symbol __ICFEDIT_region_ROM_end__ = 0x2004FFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20050000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, - block CSTACK, block HEAP }; +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x20000000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x20000000; +define symbol __ICFEDIT_region_ROM_end__ = 0x2004FFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20050000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, + block CSTACK, block HEAP }; diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f767xx_ITCM_flash.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f767xx_ITCM_flash.icf index afa86bfdf4..8d3b21a1c3 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f767xx_ITCM_flash.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f767xx_ITCM_flash.icf @@ -1,34 +1,35 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x00200000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x00200000; -define symbol __ICFEDIT_region_ROM_end__ = 0x003FFFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, - block CSTACK, block HEAP }; \ No newline at end of file +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x00200000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x00200000; +define symbol __ICFEDIT_region_ROM_end__ = 0x003FFFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, + block CSTACK, block HEAP }; +place in ITCMRAM_region { }; \ No newline at end of file diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f767xx_flash.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f767xx_flash.icf index d519df8549..ceb5a7b0c5 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f767xx_flash.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f767xx_flash.icf @@ -1,34 +1,34 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x08000000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x08000000; -define symbol __ICFEDIT_region_ROM_end__ = 0x081FFFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x08000000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x08000000; +define symbol __ICFEDIT_region_ROM_end__ = 0x081FFFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, block CSTACK, block HEAP }; \ No newline at end of file diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f767xx_sram.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f767xx_sram.icf index f3db1bb369..ea05b7fae4 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f767xx_sram.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f767xx_sram.icf @@ -1,34 +1,34 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x20000000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x20000000; -define symbol __ICFEDIT_region_ROM_end__ = 0x2004FFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20050000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, - block CSTACK, block HEAP }; +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x20000000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x20000000; +define symbol __ICFEDIT_region_ROM_end__ = 0x2004FFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20050000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, + block CSTACK, block HEAP }; diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f769xx_ITCM_flash.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f769xx_ITCM_flash.icf index afa86bfdf4..8d3b21a1c3 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f769xx_ITCM_flash.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f769xx_ITCM_flash.icf @@ -1,34 +1,35 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x00200000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x00200000; -define symbol __ICFEDIT_region_ROM_end__ = 0x003FFFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, - block CSTACK, block HEAP }; \ No newline at end of file +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x00200000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x00200000; +define symbol __ICFEDIT_region_ROM_end__ = 0x003FFFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, + block CSTACK, block HEAP }; +place in ITCMRAM_region { }; \ No newline at end of file diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f769xx_flash.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f769xx_flash.icf index d519df8549..ceb5a7b0c5 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f769xx_flash.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f769xx_flash.icf @@ -1,34 +1,34 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x08000000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x08000000; -define symbol __ICFEDIT_region_ROM_end__ = 0x081FFFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x08000000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x08000000; +define symbol __ICFEDIT_region_ROM_end__ = 0x081FFFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, block CSTACK, block HEAP }; \ No newline at end of file diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f769xx_sram.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f769xx_sram.icf index f3db1bb369..ea05b7fae4 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f769xx_sram.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f769xx_sram.icf @@ -1,34 +1,34 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x20000000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x20000000; -define symbol __ICFEDIT_region_ROM_end__ = 0x2004FFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20050000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, - block CSTACK, block HEAP }; +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x20000000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x20000000; +define symbol __ICFEDIT_region_ROM_end__ = 0x2004FFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20050000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, + block CSTACK, block HEAP }; diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f777xx_ITCM_flash.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f777xx_ITCM_flash.icf index afa86bfdf4..8d3b21a1c3 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f777xx_ITCM_flash.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f777xx_ITCM_flash.icf @@ -1,34 +1,35 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x00200000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x00200000; -define symbol __ICFEDIT_region_ROM_end__ = 0x003FFFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, - block CSTACK, block HEAP }; \ No newline at end of file +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x00200000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x00200000; +define symbol __ICFEDIT_region_ROM_end__ = 0x003FFFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, + block CSTACK, block HEAP }; +place in ITCMRAM_region { }; \ No newline at end of file diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f777xx_flash.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f777xx_flash.icf index d519df8549..ceb5a7b0c5 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f777xx_flash.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f777xx_flash.icf @@ -1,34 +1,34 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x08000000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x08000000; -define symbol __ICFEDIT_region_ROM_end__ = 0x081FFFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x08000000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x08000000; +define symbol __ICFEDIT_region_ROM_end__ = 0x081FFFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, block CSTACK, block HEAP }; \ No newline at end of file diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f777xx_sram.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f777xx_sram.icf index f3db1bb369..ea05b7fae4 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f777xx_sram.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f777xx_sram.icf @@ -1,34 +1,34 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x20000000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x20000000; -define symbol __ICFEDIT_region_ROM_end__ = 0x2004FFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20050000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, - block CSTACK, block HEAP }; +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x20000000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x20000000; +define symbol __ICFEDIT_region_ROM_end__ = 0x2004FFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20050000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, + block CSTACK, block HEAP }; diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f779xx_ITCM_flash.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f779xx_ITCM_flash.icf index afa86bfdf4..8d3b21a1c3 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f779xx_ITCM_flash.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f779xx_ITCM_flash.icf @@ -1,34 +1,35 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x00200000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x00200000; -define symbol __ICFEDIT_region_ROM_end__ = 0x003FFFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, - block CSTACK, block HEAP }; \ No newline at end of file +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x00200000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x00200000; +define symbol __ICFEDIT_region_ROM_end__ = 0x003FFFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, + block CSTACK, block HEAP }; +place in ITCMRAM_region { }; \ No newline at end of file diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f779xx_flash.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f779xx_flash.icf index d519df8549..ceb5a7b0c5 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f779xx_flash.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f779xx_flash.icf @@ -1,34 +1,34 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x08000000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x08000000; -define symbol __ICFEDIT_region_ROM_end__ = 0x081FFFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x08000000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x08000000; +define symbol __ICFEDIT_region_ROM_end__ = 0x081FFFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, block CSTACK, block HEAP }; \ No newline at end of file diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f779xx_sram.icf b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f779xx_sram.icf index f3db1bb369..ea05b7fae4 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f779xx_sram.icf +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/linker/stm32f779xx_sram.icf @@ -1,34 +1,34 @@ -/*###ICF### Section handled by ICF editor, don't touch! ****/ -/*-Editor annotation file-*/ -/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ -/*-Specials-*/ -define symbol __ICFEDIT_intvec_start__ = 0x20000000; -/*-Memory Regions-*/ -define symbol __ICFEDIT_region_ROM_start__ = 0x20000000; -define symbol __ICFEDIT_region_ROM_end__ = 0x2004FFFF; -define symbol __ICFEDIT_region_RAM_start__ = 0x20050000; -define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; -define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; -define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; -/*-Sizes-*/ -define symbol __ICFEDIT_size_cstack__ = 0x400; -define symbol __ICFEDIT_size_heap__ = 0x200; -/**** End of ICF editor section. ###ICF###*/ - - -define memory mem with size = 4G; -define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; -define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; -define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; - -define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; -define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; - -initialize by copy { readwrite }; -do not initialize { section .noinit }; - -place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; - -place in ROM_region { readonly }; -place in RAM_region { readwrite, - block CSTACK, block HEAP }; +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x20000000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x20000000; +define symbol __ICFEDIT_region_ROM_end__ = 0x2004FFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20050000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; +define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x400; +define symbol __ICFEDIT_size_heap__ = 0x200; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; +define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, + block CSTACK, block HEAP }; diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f745xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f745xx.s index d5e981fa04..22ec8e45e0 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f745xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f745xx.s @@ -1,8 +1,8 @@ ;/******************** (C) COPYRIGHT 2016 STMicroelectronics ******************** ;* File Name : startup_stm32f745xx.s ;* Author : MCD Application Team -;* Version : V1.1.0 -;* Date : 22-April-2016 +;* Version : V1.1.2 +;* Date : 23-September-2016 ;* Description : STM32F745xx devices vector table for EWARM toolchain. ;* This module performs: ;* - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f746xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f746xx.s index b9e6d55ef0..2e6e0fbe88 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f746xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f746xx.s @@ -1,8 +1,8 @@ ;/******************** (C) COPYRIGHT 2016 STMicroelectronics ******************** ;* File Name : startup_stm32f746xx.s ;* Author : MCD Application Team -;* Version : V1.1.0 -;* Date : 22-April-2016 +;* Version : V1.1.2 +;* Date : 23-September-2016 ;* Description : STM32F746xx devices vector table for EWARM toolchain. ;* This module performs: ;* - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f756xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f756xx.s index 611ee6f04f..ec5b177dc6 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f756xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f756xx.s @@ -1,8 +1,8 @@ ;/******************** (C) COPYRIGHT 2016 STMicroelectronics ******************** ;* File Name : startup_stm32f756xx.s ;* Author : MCD Application Team -;* Version : V1.1.0 -;* Date : 22-April-2016 +;* Version : V1.1.2 +;* Date : 23-September-2016 ;* Description : STM32F756xx devices vector table for EWARM toolchain. ;* This module performs: ;* - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f765xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f765xx.s index fe9a8c2349..740a362836 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f765xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f765xx.s @@ -1,8 +1,8 @@ ;/******************** (C) COPYRIGHT 2016 STMicroelectronics ******************** ;* File Name : startup_stm32f765xx.s ;* Author : MCD Application Team -;* Version : V1.1.0 -;* Date : 22-April-2016 +;* Version : V1.1.2 +;* Date : 23-September-2016 ;* Description : STM32F765xx devices vector table for EWARM toolchain. ;* This module performs: ;* - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f767xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f767xx.s index b72deef938..6d447bee99 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f767xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f767xx.s @@ -1,8 +1,8 @@ ;/******************** (C) COPYRIGHT 2016 STMicroelectronics ******************** ;* File Name : startup_stm32f767xx.s ;* Author : MCD Application Team -;* Version : V1.1.0 -;* Date : 22-April-2016 +;* Version : V1.1.2 +;* Date : 23-September-2016 ;* Description : STM32F767xx devices vector table for EWARM toolchain. ;* This module performs: ;* - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f769xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f769xx.s index 90a1a64df0..deb7818fa0 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f769xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f769xx.s @@ -1,8 +1,8 @@ ;/******************** (C) COPYRIGHT 2016 STMicroelectronics ******************** ;* File Name : startup_stm32f769xx.s ;* Author : MCD Application Team -;* Version : V1.1.0 -;* Date : 22-April-2016 +;* Version : V1.1.2 +;* Date : 23-September-2016 ;* Description : STM32F769xx devices vector table for EWARM toolchain. ;* This module performs: ;* - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f777xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f777xx.s index c18af94694..e4af6003d8 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f777xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f777xx.s @@ -1,8 +1,8 @@ ;/******************** (C) COPYRIGHT 2016 STMicroelectronics ******************** ;* File Name : startup_stm32f777xx.s ;* Author : MCD Application Team -;* Version : V1.1.0 -;* Date : 22-April-2016 +;* Version : V1.1.2 +;* Date : 23-September-2016 ;* Description : STM32F777xx devices vector table for EWARM toolchain. ;* This module performs: ;* - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f779xx.s b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f779xx.s index cd25472473..fe1542eaf8 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f779xx.s +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/iar/startup_stm32f779xx.s @@ -1,8 +1,8 @@ ;/******************** (C) COPYRIGHT 2016 STMicroelectronics ******************** ;* File Name : startup_stm32f779xx.s ;* Author : MCD Application Team -;* Version : V1.1.0 -;* Date : 22-April-2016 +;* Version : V1.1.2 +;* Date : 23-September-2016 ;* Description : STM32F779xx devices vector table for EWARM toolchain. ;* This module performs: ;* - Set the initial SP diff --git a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/system_stm32f7xx.c b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/system_stm32f7xx.c index 9e2c87f111..a7477ba955 100644 --- a/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/system_stm32f7xx.c +++ b/lib/main/CMSIS/CM7/Device/ST/STM32F7xx/Source/Templates/system_stm32f7xx.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file system_stm32f7xx.c * @author MCD Application Team - * @version V1.1.0 - * @date 22-April-2016 + * @version V1.1.2 + * @date 23-September-2016 * @brief CMSIS Cortex-M7 Device Peripheral Access Layer System Source File. * * This file provides two functions and one global variable to be called from diff --git a/lib/main/STM32F7xx_HAL_Driver/Release_Notes.html b/lib/main/STM32F7xx_HAL_Driver/Release_Notes.html index 1f258ba583..f0301be234 100644 --- a/lib/main/STM32F7xx_HAL_Driver/Release_Notes.html +++ b/lib/main/STM32F7xx_HAL_Driver/Release_Notes.html @@ -1,1074 +1,1074 @@ - - - - - - - -Release Notes for STM32F7xx HAL Drivers - - - - - -
-

 

-
- - - - - - -
- - - - - - - - - -
-

Back to Release page

-
-

Release -Notes for STM32F7xx HAL Drivers

-

Copyright -2016 STMicroelectronics

-

-
-

 

- - - - - - -
-

Update History

-

V1.1.2 / 23-September-2016

-

Main -Changes

  • General updates -to fix known defects and enhancements implementation
  • HAL - Cortex update
    • Move HAL_MPU_Disable() and - HAL_MPU_Enable() from stm32f7xx_hal_cortex.h to stm32f7xx_hal_cortex.c
    • Clear the whole MPU control - register in HAL_MPU_Disable() API
  • HAL - CRC update
    • Update HAL_CRC_DeInit() - function to reset IDR register
  • HAL - DMA update
    • Add a check on DMA stream - instance in HAL_DMA_DeInit() API
- -
  • HAL - DSI update
    • Update - HAL_DSI_ConfigHostTimeouts() and HAL_DSI_Init() functions to avoid - scratch in DSI_CCR register
  • HAL ETH update 
    • Fix wrong definitions in driver header file stm32f7_hal_eth.h
  • HAL FLASH update 
    • Update the clearing of error flags
  • HAL - GPIO update 
    • Add GPIO_AF14_LTDC definition
  • HAL - I2C update 
    • Add I2C_FIRST_AND_NEXT_FRAME - for I2C Sequential Transfer Options
  • HAL IRDA update
    • Add IRDA_CLOCKSOURCE_UNDEFINED - define
    • Add - __HAL_IRDA_FLUSH_DRREGISTER() macro for IRDA DR register flush
    • Add macros for specific flag - clear
      • __HAL_IRDA_CLEAR_FLAG()
      • __HAL_IRDA_CLEAR_PEFLAG()
      • __HAL_IRDA_CLEAR_FEFLAG()
      • __HAL_IRDA_CLEAR_NEFLAG()
      • __HAL_IRDA_CLEAR_OREFLAG()
      • __HAL_IRDA_CLEAR_IDLEFLAG()
    • Add new functions and call - backs for Transfer Abort
      • HAL_IRDA_Abort()
      • HAL_IRDA_AbortTransmit()
      • HAL_IRDA_AbortReceive()
      • HAL_IRDA_Abort_IT()
      • HAL_IRDA_AbortTransmit_IT()
      • HAL_IRDA_AbortReceive_IT()
      • HAL_IRDA_AbortCpltCallback()
      • HAL_IRDA_AbortTransmitCpltCallback()
-
      • HAL_IRDA_AbortReceiveCpltCallback()
-
  • HAL - JPEG update 
    • Update the output data - management when HAL_JPEG_Pause() is performed during the last data - sending
    • Update JPEG_FIFO_SIZE - definition
  • HAL - RCC update
    • Enable PWR only if necessary - for LSE configuration in HAL_RCC_OscConfig() API
  • HAL RTC update
    • Update - HAL_RTCEx_SetTimeStamp_IT() function implementation to clear RTC - Timestamp flag
    • Update - HAL_RTCEx_SetTamper_IT() function implementation for better management of - different RTC tampers flags
    • Update - HAL_RTCEx_SetWakeUpTimer_IT() function implementation to clear wake up - timer flag
  • HAL SMARTCARD update
    • Rename NACKState to NACKEnable - in the SMARTCARD_InitTypeDef structure
    • Add macros for specific flag - clear
      • __HAL_SMARTCARD_CLEAR_FLAG()
      • __HAL_SMARTCARD_CLEAR_PEFLAG()
      • __HAL_SMARTCARD_CLEAR_FEFLAG()
      • __HAL_SMARTCARD_CLEAR_NEFLAG() -
      • __HAL_ SMARTCARD_CLEAR_OREFLAG()
      • __HAL_ SMARTCARD_CLEAR_IDLEFLAG()
    • Add new functions and call backs - for Transfer Abort
      • HAL_ SMARTCARD_Abort()
      • HAL_ SMARTCARD_AbortTransmit()
      • HAL_ SMARTCARD_AbortReceive()
      • HAL_ SMARTCARD_Abort_IT()
      • HAL_ SMARTCARD_AbortTransmit_IT()
      • HAL_ SMARTCARD_AbortReceive_IT()
      • HAL_ SMARTCARD_AbortCpltCallback()
      • HAL_ SMARTCARD_AbortTransmitCpltCallback()
      • HAL_ SMARTCARD_AbortReceiveCpltCallback()
  • HAL SPI update
    • Update SPI_EndRxTxTransaction() function to RX FiFo at the end of each transaction
    • Add HAL_SPI_STATE_ABORT in the - HAL_SPI_StateTypeDef enum
    • Add new functions and call - backs for Transfer Abort
      • HAL_SPI_Abort ()
      • HAL_SPI_Abort_IT()
      • HAL_SPI_AbortCpltCallback()
- - - -
  • HAL - UART update
    • Update HAL_UART_Receive_IT() - and HAL_UART_DMAStop() functions implementations to manage Parity error - interrupt
  • HAL - USART update
    • Update HAL_USART_Init() function by removing the clear of CLKEN bit
    • Update HAL_USART_Receive_IT() - and HAL_USART_DMAStop() functions implementations to manage Parity error - interrupt
-
  • HAL USB update
    • Update PENA bit clearing in - OTG_HPRT0 register
-

V1.1.1 / 01-July-2016

-

Main -Changes

  • HAL DMA update 
    • Update HAL_DMA_PollForTransfer() function implementation to avoid early TIMEOUT error.
  • HAL JPEG update
    • Update HAL_JPEG_ConfigEncoding() function to properly set the ImageHeight and ImageWidth
  • HAL SPI update
    • Update SPI_DMATransmitReceiveCplt() function to properly handle the CRC and avoid conditional statement duplication

V1.1.0 / 22-April-2016

-

Main -Changes

  • Official release to add the support of STM32F765xx, STM32F767xx, STM32F768xx, STM32F769xx, STM32F777xx, STM32F778xx and STM32F779xx devices
  • General updates -to fix known defects and enhancements implementation
  • Add new HAL drivers for DFSDM, DSI, JPEG and MDIOS peripherals
  • Enhance HAL delay and timebase implementation
    • Add new -drivers stm32f7xx_hal_timebase_tim_template.c, stm32f7xx_hal_timebase_rtc_alarm_template.c and -stm32f7xx_hal_timebase_rtc_wakeup_template.c which override the native HAL time -base functions (defined as weak) to either use the TIM or the RTC as time base tick source. For -more details about the usage of these drivers, please refer to HAL\HAL_TimeBase -examples and FreeRTOS-based applications
  • The following changes done on the HAL drivers require an update on the -application code based on HAL V1.0.4
    • HAL UART, USART, IRDA, SMARTCARD, SPI, I2C, QSPI (referenced as PPP here below) drivers
      • Add PPP error management during DMA process. This requires the following updates on user application:
        • Configure and enable -the PPP IRQ in HAL_PPP_MspInit() function
        • In stm32f7xx_it.c file, -PPP_IRQHandler() -function: add a call to -HAL_PPP_IRQHandler() function -
        • Add and customize -the Error Callback API: HAL_PPP_ErrorCallback()
-
    • HAL I2C (referenced as PPP here below) drivers: -
      • Update to avoid waiting on STOPF/BTF/AF flag under DMA ISR by using the PPP end of transfer interrupt in the DMA transfer process. This requires the following updates on user application:
        • Configure and enable -the PPP IRQ in HAL_PPP_MspInit() function
      -
        • In stm32f7xx_it.c file, -PPP_IRQHandler() -function: add a call to -HAL_PPP_IRQHandler() function
-
    • HAL IWDG driver: rework overall driver for better implementation
      • Remove HAL_IWDG_Start(), HAL_IWDG_MspInit() and HAL_IWDG_GetState() APIs
    • HAL WWDG driver: rework overall driver for better implementation -
      • Remove HAL_WWDG_Start(), HAL_WWDG_Start_IT(), -HAL_WWDG_MspDeInit() and HAL_WWDG_GetState() APIs  -
      • Update the HAL_WWDG_Refresh(WWDG_HandleTypeDef *hwwdg, uint32_t counter)  function and API  by removing the  "counter" parameter
    • HAL QSPI driver:  Enhance the DMA transmit process by using PPP TC interrupt instead of waiting on TC flag under DMA ISR. This requires the following updates on user application:
      • Configure and enable -the QSPI IRQ in HAL_QSPI_MspInit() function
      • In stm32f7xx_it.c file, QSPI_IRQHandler() -function: add a call to -HAL_QSPI_IRQHandler() function
-
    • HAL CEC driver:  Overall driver rework with compatibility break versus previous HAL version
      • Remove HAL CEC polling Process functions: HAL_CEC_Transmit() and HAL_CEC_Receive() -
      • Remove -HAL CEC receive interrupt process function HAL_CEC_Receive_IT() -and enable the "receive"  mode during the Init phase -
      • Rename HAL_CEC_GetReceivedFrameSize() funtion to HAL_CEC_GetLastReceivedFrameSize()
        -
      • Add new HAL APIs: HAL_CEC_SetDeviceAddress() and -HAL_CEC_ChangeRxBuffer() -
      • Remove the 'InitiatorAddress' field from the CEC_InitTypeDef -structure and manage it as a parameter in the HAL_CEC_Transmit_IT() function -
      • Add new parameter 'RxFrameSize' in HAL_CEC_RxCpltCallback() function -
      • Move CEC Rx buffer pointer from CEC_HandleTypeDef structure to -CEC_InitTypeDef structure
  • HAL CAN update 
    • Add the support of CAN3
  • HAL CEC update
    • Overall driver rework with break of compatibility with HAL -V1.0.4
      • Remove the HAL CEC polling Process: HAL_CEC_Transmit() and HAL_CEC_Receive()
-
      • Remove the HAL CEC receive interrupt process (HAL_CEC_Receive_IT()) and manage the "Receive" mode enable within the Init phase -
      • Rename HAL_CEC_GetReceivedFrameSize() function to HAL_CEC_GetLastReceivedFrameSize() function
      • Add new HAL APIs: HAL_CEC_SetDeviceAddress() and -HAL_CEC_ChangeRxBuffer()
      • Remove the 'InitiatorAddress' field from the CEC_InitTypeDef -structure and manage it as a parameter in the HAL_CEC_Transmit_IT() function
      • Add new parameter 'RxFrameSize' in HAL_CEC_RxCpltCallback() function
      • Move CEC Rx buffer pointer from CEC_HandleTypeDef structure to -CEC_InitTypeDef structure
-
    • Update driver to implement the new CEC state machine:
      • Add new "rxState" field in -CEC_HandleTypeDef structure to provide the CEC -state -information related to Rx Operations
      • Rename "state" -field in CEC_HandleTypeDef structure to "gstate": CEC state information -related to global Handle management and Tx Operations -
      • Update CEC process -to manage the new CEC states. -
      • Update __HAL_CEC_RESET_HANDLE_STATE() macro to handle the new CEC -state parameters (gState, rxState)
  • HAL DMA update 
    • Add -new APIs HAL_DMA_RegisterCallback() and HAL_DMA_UnRegisterCallback to -register/unregister the different callbacks identified by -the enum typedef HAL_DMA_CallbackIDTypeDef
    • Add new API HAL_DMA_Abort_IT() to abort DMA transfer under interrupt context
      • The new registered Abort callback is called when DMA transfer abortion is completed
    • Add the check of -compatibility between FIFO threshold level and size of the memory burst in the -HAL_DMA_Init() API -
    • Add new Error Codes: -HAL_DMA_ERROR_PARAM, HAL_DMA_ERROR_NO_XFER and -HAL_DMA_ERROR_NOT_SUPPORTED
    • Remove all DMA states -related to MEM0/MEM1 in HAL_DMA_StateTypeDef
  • HAL DMA2D update 
    • Update the -HAL_DMA2D_DeInit() function to: -
      • Abort transfer in case -of ongoing DMA2D transfer
      -
      • Reset DMA2D control -registers
    • Update -HAL_DMA2D_Abort() to disable DMA2D interrupts after stopping transfer
    • Optimize -HAL_DMA2D_IRQHandler() by reading status registers only once -
    • Update -HAL_DMA2D_ProgramLineEvent() function to: -
      • Return HAL error state -in case of wrong line value
      -
      • Enable line interrupt -after setting the line watermark configuration
    • Add new HAL_DMA2D_CLUTLoad() and HAL_DMA2D_CLUTLoad_IT() -functions to start DMA2D CLUT loading
      • HAL_DMA2D_CLUTLoading_Abort() -function to abort the DMA2D CLUT loading
      • HAL_DMA2D_CLUTLoading_Suspend() -function to suspend the DMA2D CLUT loading
      • HAL_DMA2D_CLUTLoading_Resume() -function to resume the DMA2D CLUT loading
    • Add new DMA2D dead time -management:
      • HAL_DMA2D_EnableDeadTime() -function to enable DMA2D dead time feature
      • HAL_DMA2D_DisableDeadTime() -function to disable DMA2D dead time feature
      • HAL_DMA2D_ConfigDeadTime() -function to configure dead time
    • Update the name of -DMA2D Input/Output color mode defines to be more clear for user (DMA2D_INPUT_XXX -for input layers Colors, DMA2D_OUTPUT_XXX for output framebuffer -Colors)
- -
  • HAL DCMI update 
    • Rename DCMI_DMAConvCplt -to DCMI_DMAXferCplt -
    • Update HAL_DCMI_Start_DMA() function to Enable the DCMI peripheral -
    • Add new timeout -implementation based on cpu cycles for DCMI stop -
    • Add HAL_DCMI_Suspend() -function to suspend DCMI capture -
    • Add HAL_DCMI_Resume() -function to resume capture after DCMI suspend -
    • Update lock mechanism -for DCMI process -
    • Update HAL_DCMI_IRQHandler() function to: -
      • Add error management in -case DMA errors through XferAbortCallback() and -HAL_DMA_Abort_IT()
      -
      • Optimize code by using -direct register read
    • Move -the content of the stm32f7xx_hal_dcmi_ex.c/.h files to common driver -files (the extension files are kept empty for projects compatibility -reason)
  • HAL FLASH update 
    • Add the support of Dual BANK feature
    • Add __HAL_FLASH_CALC_BOOT_BASE_ADR() macro to calculate the FLASH Boot Base Adress
    • Move Flash total sector define to CMSIS header files
  • HAL FMC update
    • Update FMC_NORSRAM_Init() to remove the Burst access mode configuration
    • Update FMC_SDRAM_Timing_Init() to fix initialization issue when configuring 2 SDRAM banks
  • HAL HCD update
    • Update HCD_Port_IRQHandler() to be compliant with new Time base implementation
  • HAL -I2C update -
    • Add the support of I2C fast mode plus (FM+)
    • Update Polling management:
      • The Timeout value must be estimated for the overall process duration: the Timeout measurement is cumulative
    -
    • Add the management of Abort service: Abort DMA transfer through interrupt
      • In the case of Master Abort IT transfer usage:
        • Add new user HAL_I2C_AbortCpltCallback() to inform user of the end of abort process
        • A new abort state is defined in the HAL_I2C_StateTypeDef structure
    -
    • Add the management of I2C peripheral errors, ACK -failure and STOP condition detection during DMA process. This requires the following updates -on user application:
      • Configure and enable the I2C IRQ in HAL_I2C_MspInit() function
      • In stm32f7xx_it.c file, I2C_IRQHandler() function: add a call to HAL_I2C_IRQHandler() function
      • Add and customize the Error Callback API: HAL_I2C_ErrorCallback()
      • Refer to the I2C_EEPROM or I2C_TwoBoards_ComDMA project examples usage of the API
    • Add the support of I2C repeated start feature: -
      • With the following new APIs
      -
        • HAL_I2C_Master_Sequential_Transmit_IT() -
        • HAL_I2C_Master_Sequential_Receive_IT() -
        • HAL_I2C_Master_Abort_IT() -
        • HAL_I2C_Slave_Sequential_Transmit_IT() -
        • HAL_I2C_Slave_Sequential_Receive_IT() -
        • HAL_I2C_EnableListen_IT() -
        • HAL_I2C_DisableListen_IT()
      -
      • Add new user callbacks:
      -
        • HAL_I2C_ListenCpltCallback()
        • HAL_I2C_AddrCallback()
      -
    • Several -updates on HAL I2C driver to implement the new I2C state machine: -
      • Add new API to get the I2C mode: -HAL_I2C_GetMode() -
      • Update I2C process to -manage the new I2C states
    -
  • HAL IWDG update
    • Overall rework of the driver for a more efficient implementation
      • Remove the following APIs:
        • HAL_IWDG_Start()
        • HAL_IWDG_MspInit()
        • HAL_IWDG_GetState()
      • Update implementation:
        • HAL_IWDG_Init() : this function insures the configuration and the start of the IWDG counter
        • HAL_IWDG_Refresh() : this function insures the reload of the IWDG counter
      • Refer to the following example to identify the changes: IWDG_Example
  • HAL LPTIM update
    • Update HAL_LPTIM_TimeOut_Start_IT() and HAL_LPTIM_Counter_Start_IT( ) APIs -to configure WakeUp Timer EXTI interrupt to be able to wakeup MCU from low power -mode by pressing the EXTI line -
    • Update HAL_LPTIM_TimeOut_Stop_IT() and HAL_LPTIM_Counter_Stop_IT( ) APIs to -disable WakeUp Timer EXTI interrupt
  • HAL LTDC update
    • Update -HAL_LTDC_IRQHandler() to manage the case of reload interrupt
    • Add LTDC extension driver needed with DSI
    • Add HAL_LTDC_SetPitch() function for pitch reconfiguration
    • Add new callback API -HAL_LTDC_ReloadEventCallback() -
    • Add HAL_LTDC_Reload() -to configure LTDC reload feature -
    • Add new No Reload LTDC -variant APIs
      -
      • HAL_LTDC_ConfigLayer_NoReload() -to configure the LTDC Layer according to the specified without reloading -
      • HAL_LTDC_SetWindowSize_NoReload() -to set the LTDC window size without reloading -
      • HAL_LTDC_SetWindowPosition_NoReload() -to set the LTDC window position without reloading -
      • HAL_LTDC_SetPixelFormat_NoReload() -to reconfigure the pixel format without reloading -
      • HAL_LTDC_SetAlpha_NoReload() -to reconfigure the layer alpha value without reloading -
      • HAL_LTDC_SetAddress_NoReload() -to reconfigure the frame buffer Address without reloading -
      • HAL_LTDC_SetPitch_NoReload() -to reconfigure the pitch for specific cases -
      • HAL_LTDC_ConfigColorKeying_NoReload() -to configure the color keying without reloading -
      • HAL_LTDC_EnableColorKeying_NoReload() -to enable the color keying without reloading -
      • HAL_LTDC_DisableColorKeying_NoReload() -to disable the color keying without reloading -
      • HAL_LTDC_EnableCLUT_NoReload() -to enable the color lookup table without reloading -
      • HAL_LTDC_DisableCLUT_NoReload() -to disable the color lookup table without -reloading
      • Note: -Variant functions with “_NoReload” post fix allows to set the LTDC -configuration/settings without immediate reload. This is useful in case -when the program requires to modify several LTDC settings (on one or -both layers) then applying (reload) these settings in one shot by -calling the function “HAL_LTDC_Reload”
-
  • HAL NOR update
    • Update NOR_ADDR_SHIFT macro implementation
  • HAL PCD update
    • Update HAL_PCD_IRQHandler() to get HCLK frequency before setting TRDT value
  • HAL QSPI update
    • Update to manage QSPI error management during DMA process
    • Improve the DMA transmit process by using QSPI TC interrupt instead of waiting loop on TC flag under DMA ISR
    • These two improvements require the following updates on user application:
      • Configure and enable the QSPI IRQ in HAL_QSPI_MspInit() function
      • In stm32f7xx_it.c file, QSPI_IRQHandler() function: add a call to HAL_QSPI_IRQHandler() function
      • Add and customize the Error Callback API: HAL_QSPI_ErrorCallback()
    • Add -the management of non-blocking transfer abort service: HAL_QSPI_Abort_IT(). In -this case the user must:
      • Add new callback HAL_QSPI_AbortCpltCallback() to inform user at the end of abort process
      • A new value of State in the HAL_QSPI_StateTypeDef provides the current state during the abort phase
    • Polling management update:
      • The Timeout value user must be estimated for the overall process duration: the Timeout measurement is cumulative. 
    • Refer to the following examples, which describe the changes:
      • QSPI_ReadWrite_DMA
      • QSPI_MemoryMapped
      • QSPI_ExecuteInPlace
    • Add two new APIs for the QSPI fifo threshold: -
      • HAL_QSPI_SetFifoThreshold(): configure the FIFO threshold of -the QSPI -
      • HAL_QSPI_GetFifoThreshold(): give the current FIFO -threshold
      -
    • Fix wrong data size management in HAL_QSPI_Receive_DMA()
  • HAL RCC update
    • Update HAL_RCC_PeriphCLKConfig() function to adjust the SystemCoreClock
    • Optimize HAL_RCC_ClockConfig() function code
    • Optimize internal oscillators and PLL startup times
  • HAL RTC update 
    • Update HAL_RTC_GetTime() with proper 'SubSeconds' and 'SecondFraction' management
  • HAL SAI update 
    • Update SAI state in case of TIMEOUT error within the HAL_SAI_Transmit() / HAL_SAI_Receive() -
    • Update HAL_SAI_IRQHandler: -
      • Add error management in -case DMA errors through XferAbortCallback() and HAL_DMA_Abort_IT() -
      • Add error management in -case of IT
    • Move -SAI_BlockSynchroConfig() and SAI_GetInputClock() functions to -stm32f7xx_hal_sai.c/.h files (extension files are kept empty for -projects compatibility reason)
-
  • HAL SPDIFRX update
    • Overall driver update for wait on flag management optimization
  • HAL SPI update
    • Overall driver optimization to improve performance in polling/interrupt mode to reach maximum peripheral frequency
      • Polling mode: -
        • Replace the use of SPI_WaitOnFlagUnitTimeout() function by "if" -statement to check on RXNE/TXE flage while transferring -data
-
      •  Interrupt mode:
        • Minimize access on SPI registers -
      • All modes:
        • Add the USE_SPI_CRC switch to minimize the number of statements when CRC calculation is disabled
        • Update timeout management to check on global processes
        • Update error code management in all processes
    • Update DMA process: -
      • Add the management of SPI peripheral errors during DMA process. This requires the following updates in -the user application:
        • Configure and enable the SPI IRQ in HAL_SPI_MspInit() function
        • In stm32f7xx_it.c file, SPI_IRQHandler() function: add a call to HAL_SPI_IRQHandler() function
        • Add and customize the Error Callback API: HAL_SPI_ErrorCallback()
        • Refer to the following example which describe the changes: SPI_FullDuplex_ComDMA
      -
  • HAL TIM update 
    • Update HAL_TIM_ConfigOCrefClear() function for proper configuration of the SMCR register
    • Add new function HAL_TIMEx_ConfigBreakInput() to configure the break input source
  • HAL UART, USART, SMARTCARD and IRDA (referenced as PPP here below) update -
    • Update Polling management:
      • The user Timeout value must be estimated for the overall process duration: the Timeout measurement is cumulative
    • Update DMA process:
      • Update the management of PPP peripheral errors during DMA process. This requires the following updates in user application:
        • Configure and enable the PPP IRQ in HAL_PPP_MspInit() function
        • In stm32f7xx_it.c file, PPP_IRQHandler() function: add a call to HAL_PPP_IRQHandler() function
        • Add and customize the Error Callback API: HAL_PPP_ErrorCallback()
  • HAL WWDG update 
    • Overall rework of the driver for more efficient implementation
      • Remove the following APIs:
        • HAL_WWDG_Start()
        • HAL_WWDG_Start_IT()
        • HAL_WWDG_MspDeInit()
        • HAL_WWDG_GetState()
      • Update implementation:
        • HAL_WWDG_Init()
          • A new parameter in the Init Structure: EWIMode
        • HAL_WWDG_MspInit()
        • HAL_WWDG_Refresh() 
          • This function insures the reload of the counter
          • The "counter" parameter has been removed
        • HAL_WWDG_IRQHandler()
        • HAL_WWDG_EarlyWakeupCallback() is the new prototype of HAL_WWDG_WakeupCallback()
    • Refer to the following example to identify the changes: WWDG_Example

V1.0.4 / 09-December-2015

-

Main -Changes

  • HAL Generic update
    • Update HAL -weak empty callbacks to prevent unused argument compilation warnings with some -compilers by calling the following line: -
      • UNUSED(hppp);
  • HAL ETH update 
    • Update HAL_ETH_Init() function to add timeout on the Software reset management

V1.0.3 / 13-November-2015

-

Main -Changes

  • General updates -to fix known defects and enhancements implementation
  • One change done on the HAL CRYP requires an update on -the application code based on HAL V1.0.2 -
    • Update -HAL_CRYP_DESECB_Decrypt() API to invert pPlainData and pCypherData -parameters
  • HAL Generic update
    • Update HAL -weak empty callbacks to prevent unused argument compilation warnings with some -compilers by calling the following line: -
      • UNUSED(hppp);
    • Remove references to STM32CubeMX and MicroXplorer from stm32f7xx_hal_msp_template.c file
  • HAL ADC update
    • Replace ADC_CHANNEL_TEMPSENSOR definition from ADC_CHANNEL_16 to ADC_CHANNEL_18  
    • Update HAL ADC driver state machine for code efficiency
    • Add new literal: ADC_INJECTED_SOFTWARE_START to be used as possible -value for the ExternalTrigInjecConvEdge parameter in the ADC_InitTypeDef -structure to select the ADC software trigger mode.
  • HAL CORTEX update -
    • Remove duplication -for __HAL_CORTEX_SYSTICKCLK_CONFIG() macro
  • HAL CRYP update
    • Update HAL_CRYP_DESECB_Decrypt() API to fix the inverted pPlainData and pCypherData parameters issue
  • HAL FLASH update
    • Update OB_IWDG_STOP_ACTIVE definition
    • Update OB_RDP_LEVEL_x definition by proper values
    • Update FLASH_MassErase() function to consider the voltage range parameter in the mass erase configuration
  • HAL RCC update
    • update values for LSE Drive capability defines
    • update PLLN min value 50 instead of 100
    • add RCC_PLLI2SP_DIVx defines for PLLI2SP clock divider
    • Update __HAL_RCC_USB_OTG_FS_CLK_DISABLE() macro to remove the disable of the SYSCFG 
    • Update HAL_RCCEx_GetPeriphCLKFreq() function for proper SAI clock configuration
  • HAL SAI update
    • update for proper management of the external synchronization input selection
      • update of HAL_SAI_Init () funciton
      • update definition of SAI_Block_SyncExt and SAI_Block_Synchronization groups
    • update SAI_SLOTACTIVE_X  defines values
    • update HAL_SAI_Init() function for proper companding mode management
    • update SAI_Transmit_ITxxBit() functions to add the check on transfer counter before writing new data to SAIx_DR registers
    • update SAI_FillFifo() function to avoid issue when the number of data to transmit is smaller than the FIFO size
    • update HAL_SAI_EnableRxMuteMode() function for proper mute management
    • update SAI_InitPCM() function to support 24bits configuration
  • HAL SD update
    • update HAL_SD_Get_CardInfo() to properly support high capacity cards
  • HAL SPDIFRX update
    • update SPDIFRX_DMARxCplt() function implementation to check on circular mode before disabling the DMA
  • HAL TIM update
    • Update HAL_TIM_ConfigClockSource() function implementation for proper parameters check
  • HAL UART update
    • Update __HAL_UART_CLEAR_IT macro for proper functionning 
  • ll FMC update
    • add FMC_PAGE_SIZE_512 define
  • ll SDMMC update
    • update SDMMC_SetSDMMCReadWaitMode() function for proper functionning

V1.0.2 / 21-September-2015

-

Main -Changes

  • HAL Generic update
    • stm32f7xx_hal.conf_template.h: update HSE_STARTUP_TIMEOUT
    • stm32f7xx_hal_def.h: update the quotation marks used in #error"USE_RTOS should be 0 in the current HAL release"
  • HAL DMA update
    • Overall -driver update for code optimization
      • add -StreamBaseAddress and StreamIndex new fields in the DMA_HandleTypeDef -structure -
      • add -DMA_Base_Registers private structure -
      • add static function -DMA_CalcBaseAndBitshift() -
      • update -HAL_DMA_Init() function to use the new added static function -
      • update -HAL_DMA_DeInit() function to optimize clear flag operations -
      • update -HAL_DMA_Start_IT() function to optimize interrupts enable -
      • update -HAL_DMA_PollForTransfer() function to optimize check on flags -
      • update -HAL_DMA_IRQHandler() function to optimize interrupt flag management
  • HAL ETH update
    • remove duplicated macro IS_ETH_RX_MODE()
  • HAL GPIO update
    • Rename -GPIO_SPEED_LOW define to GPIO_SPEED_FREQ_LOW -
    • Rename -GPIO_SPEED_MEDIUM define to GPIO_SPEED_FREQ_MEDIUM -
    • Rename -GPIO_SPEED_FAST define to GPIO_SPEED_FREQ_HIGH -
    • Rename -GPIO_SPEED_HIGH define to GPIO_SPEED_FREQ_VERY_HIGH
  • HAL HASH update
    • Rename -HAL_HASH_STATETypeDef to HAL_HASH_StateTypeDef -
    • Rename -HAL_HASH_PhaseTypeDef to HAL_HASHPhaseTypeDef
  • HAL RCC update
    • update values for LSE Drive capability defines
    • update PLLN/PLLI2SN/PLLSAI VCO min value 100MHz instead of 192MHz
    • add __HAL_RCC_MCO1_CONFIG() and __HAL_RCC_MCO2_CONFIG() macros
    • update HAL_RCCEx_PeriphCLKConfig() function to reset the Backup domain only if the RTC Clock source selection is modified 
  • HAL TIM update
    • update the implementation of __HAL_TIM_SET_COMPARE() macro
    • remove useless assert() in HAL_TIM_PWM_ConfigChannel(), TIM_OC2_SetConfig() and HAL_TIM_PWM_ConfigChannel() functions
  • HAL CAN update
    • add the clear flag ERRI bit in HAL_CAN_IRQHandler()
  • HAL I2S update
    • update I2S HAL_I2S_Transmit() API to keep the check on busy flag only for the slave
  • HAL QSPI update
    • Add __HAL_QSPI_CLEAR_FLAG() before QSPI_Config()
  • HAL UART update
    • Remove -enabling of ERR IT source and PE source from HAL_UART_Transmit_IT() and -remove the corresponding disabling ERR/PE IT from UART_EndTransmit_IT()
  • HAL PCD update 
    • Clean status phase received interrupt when DMA mode enabled 
  • HAL HCD update
    • Update to use local -variable in USB Host channel re-activation
  • ll FMC update
    • update the define FMC Write FIFO Disable/Enable: FMC_WRITE_FIFO_DISABLE and FMC_WRITE_FIFO_ENABLE
    • remove return HAL_ERROR from FMC_SDRAM_SendCommand() function

V1.0.1 / 25-June-2015

-

Main -Changes

  • General updates -to fix known defects and enhancements implementation
  • HAL CRC update
    • update __HAL_CRC_SET_IDR() macro implementation to use WRITE_REG() instead of MODIFY_REG()
  • HAL CEC update
    • update timeout management in HAL_CEC_Transmit() and HAL_CEC_Receive() functions
  • HAL Cortex update
    • update HAL_MPU_ConfigRegion() function to be misra compliant
  • HAL ETH update
    • Remove -duplicated IS_ETH_DUPLEX_MODE() and IS_ETH_RX_MODE() macros
    • Remove -illegal space ETH_MAC_READCONTROLLER_FLUSHING macro
    • Update -ETH_MAC_READCONTROLLER_XXX defined values (XXX can be IDLE, READING_DATA and -READING_STATUS)
  • HAL FLASH update
    • update FLASH_OB_GetRDP() function to return uint8_t  instead of FlagStatus
    • update OB_RDP_LEVELx definition
    • add __HAL_FLASH_GET_LATENCY() macro
  • HAL HASH update
    • update -HASH_DMAXferCplt() and HASHEx_DMAXferCplt() functions to properly -configure the number of valid bits in last word of the message
    • update HAL_HASH_SHA1_Accumulate() function to check on the length of the input buffer
    • update -HAL_HASH_MODE_Start_IT() functions (Mode stands for MD5, SHA1, SHA224 and SHA256 ) to :
      • Fix processing -fail for small input buffers -
      • to unlock -the process and call return HAL_OK at the end of HASH processing to avoid -incorrect repeating software -
      • properly to manage -the HashITCounter efficiency -
      • Update to call the -HAL_HASH_InCpltCallback() at the end of the complete buffer instead -of -every each 512 bits
    • update HASH_IT_DINI and HASH_IT_DCI definition
    • update __HAL_HASH_GET_FLAG() macro definition
  • HAL I2S update
    • update HAL_I2S_Transmit() function to ensure the waiting on Busy flag in case of slave mode selection
  • HAL RTC update
    • update HAL_RTCEx_SetWakeUpTimer() and HAL_RTCEx_SetWakeUpTimer_IT() functions to properly check on WUTWF flag
    • rename RTC_TIMESTAMPPIN_PI8 define to RTC_TIMESTAMPPIN_POS1
    • rename RTC_TIMESTAMPPIN_PC1 define to RTC_TIMESTAMPPIN_POS2
    • update __HAL_RTC_WAKEUPTIMER_CLEAR_FLAG() macro definition
    • update __HAL_RTC_TAMPER_GET_IT() macro definition
    • update __HAL_RTC_TAMPER_CLEAR_FLAG() macro definition
    • update __HAL_RTC_TIMESTAMP_CLEAR_FLAG() macro definition
    • update __HAL_RTC_TAMPER_TIMESTAMP_EXTI_GET_FLAG() macro definition
    • add RTC_TAMPCR_TAMPXE and RTC_TAMPCR_TAMPXIE defines
  • HAL SMARTCARD update
    • add SMARTCARD_FLAG_IDLE, SMARTCARD_IT_IDLE and  SMARTCARD_CLEAR_IDLEF defines
  • HAL UART update
    • update HAL_UART_DMAResume() function to clear overrun flag before resuming the Rx transfer
    • update UART_FLAG_SBKF definition
  • HAL USART update
    • update HAL_USART_DMAResume() function to clear overrun flag before resuming the Rx transfer
  • LL FMC update
    • update NAND timing maximum values
  • LL USB update -
    • USB_FlushTxFifo API: -update to flush all Tx FIFO -
    • Update to use local -variable in USB Host channel re-activation
- -

V1.0.0 / 12-May-2015

-

Main -Changes

  • First official release for STM32F756xx/746xx/745xx -devices
- -

License

-
-
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. -
  3. 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.
  4. -
  5. Neither the -name of STMicroelectronics nor the names of its contributors may be -used to endorse or promote products derived
    -
  6. -
-       -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.
-
- -
-
-

For -complete documentation on STM32 Microcontrollers visit www.st.com/STM32

-
-

-
-
-

 

-
+ + + + + + + +Release Notes for STM32F7xx HAL Drivers + + + + + +
+

 

+
+ + + + + + +
+ + + + + + + + + +
+

Back to Release page

+
+

Release +Notes for STM32F7xx HAL Drivers

+

Copyright +2016 STMicroelectronics

+

+
+

 

+ + + + + + +
+

Update History

+

V1.1.2 / 23-September-2016

+

Main +Changes

  • General updates +to fix known defects and enhancements implementation
  • HAL + Cortex update
    • Move HAL_MPU_Disable() and + HAL_MPU_Enable() from stm32f7xx_hal_cortex.h to stm32f7xx_hal_cortex.c
    • Clear the whole MPU control + register in HAL_MPU_Disable() API
  • HAL + CRC update
    • Update HAL_CRC_DeInit() + function to reset IDR register
  • HAL + DMA update
    • Add a check on DMA stream + instance in HAL_DMA_DeInit() API
+ +
  • HAL + DSI update
    • Update + HAL_DSI_ConfigHostTimeouts() and HAL_DSI_Init() functions to avoid + scratch in DSI_CCR register
  • HAL ETH update 
    • Fix wrong definitions in driver header file stm32f7_hal_eth.h
  • HAL FLASH update 
    • Update the clearing of error flags
  • HAL + GPIO update 
    • Add GPIO_AF14_LTDC definition
  • HAL + I2C update 
    • Add I2C_FIRST_AND_NEXT_FRAME + for I2C Sequential Transfer Options
  • HAL IRDA update
    • Add IRDA_CLOCKSOURCE_UNDEFINED + define
    • Add + __HAL_IRDA_FLUSH_DRREGISTER() macro for IRDA DR register flush
    • Add macros for specific flag + clear
      • __HAL_IRDA_CLEAR_FLAG()
      • __HAL_IRDA_CLEAR_PEFLAG()
      • __HAL_IRDA_CLEAR_FEFLAG()
      • __HAL_IRDA_CLEAR_NEFLAG()
      • __HAL_IRDA_CLEAR_OREFLAG()
      • __HAL_IRDA_CLEAR_IDLEFLAG()
    • Add new functions and call + backs for Transfer Abort
      • HAL_IRDA_Abort()
      • HAL_IRDA_AbortTransmit()
      • HAL_IRDA_AbortReceive()
      • HAL_IRDA_Abort_IT()
      • HAL_IRDA_AbortTransmit_IT()
      • HAL_IRDA_AbortReceive_IT()
      • HAL_IRDA_AbortCpltCallback()
      • HAL_IRDA_AbortTransmitCpltCallback()
+
      • HAL_IRDA_AbortReceiveCpltCallback()
+
  • HAL + JPEG update 
    • Update the output data + management when HAL_JPEG_Pause() is performed during the last data + sending
    • Update JPEG_FIFO_SIZE + definition
  • HAL + RCC update
    • Enable PWR only if necessary + for LSE configuration in HAL_RCC_OscConfig() API
  • HAL RTC update
    • Update + HAL_RTCEx_SetTimeStamp_IT() function implementation to clear RTC + Timestamp flag
    • Update + HAL_RTCEx_SetTamper_IT() function implementation for better management of + different RTC tampers flags
    • Update + HAL_RTCEx_SetWakeUpTimer_IT() function implementation to clear wake up + timer flag
  • HAL SMARTCARD update
    • Rename NACKState to NACKEnable + in the SMARTCARD_InitTypeDef structure
    • Add macros for specific flag + clear
      • __HAL_SMARTCARD_CLEAR_FLAG()
      • __HAL_SMARTCARD_CLEAR_PEFLAG()
      • __HAL_SMARTCARD_CLEAR_FEFLAG()
      • __HAL_SMARTCARD_CLEAR_NEFLAG() +
      • __HAL_ SMARTCARD_CLEAR_OREFLAG()
      • __HAL_ SMARTCARD_CLEAR_IDLEFLAG()
    • Add new functions and call backs + for Transfer Abort
      • HAL_ SMARTCARD_Abort()
      • HAL_ SMARTCARD_AbortTransmit()
      • HAL_ SMARTCARD_AbortReceive()
      • HAL_ SMARTCARD_Abort_IT()
      • HAL_ SMARTCARD_AbortTransmit_IT()
      • HAL_ SMARTCARD_AbortReceive_IT()
      • HAL_ SMARTCARD_AbortCpltCallback()
      • HAL_ SMARTCARD_AbortTransmitCpltCallback()
      • HAL_ SMARTCARD_AbortReceiveCpltCallback()
  • HAL SPI update
    • Update SPI_EndRxTxTransaction() function to RX FiFo at the end of each transaction
    • Add HAL_SPI_STATE_ABORT in the + HAL_SPI_StateTypeDef enum
    • Add new functions and call + backs for Transfer Abort
      • HAL_SPI_Abort ()
      • HAL_SPI_Abort_IT()
      • HAL_SPI_AbortCpltCallback()
+ + + +
  • HAL + UART update
    • Update HAL_UART_Receive_IT() + and HAL_UART_DMAStop() functions implementations to manage Parity error + interrupt
  • HAL + USART update
    • Update HAL_USART_Init() function by removing the clear of CLKEN bit
    • Update HAL_USART_Receive_IT() + and HAL_USART_DMAStop() functions implementations to manage Parity error + interrupt
+
  • HAL USB update
    • Update PENA bit clearing in + OTG_HPRT0 register
+

V1.1.1 / 01-July-2016

+

Main +Changes

  • HAL DMA update 
    • Update HAL_DMA_PollForTransfer() function implementation to avoid early TIMEOUT error.
  • HAL JPEG update
    • Update HAL_JPEG_ConfigEncoding() function to properly set the ImageHeight and ImageWidth
  • HAL SPI update
    • Update SPI_DMATransmitReceiveCplt() function to properly handle the CRC and avoid conditional statement duplication

V1.1.0 / 22-April-2016

+

Main +Changes

  • Official release to add the support of STM32F765xx, STM32F767xx, STM32F768xx, STM32F769xx, STM32F777xx, STM32F778xx and STM32F779xx devices
  • General updates +to fix known defects and enhancements implementation
  • Add new HAL drivers for DFSDM, DSI, JPEG and MDIOS peripherals
  • Enhance HAL delay and timebase implementation
    • Add new +drivers stm32f7xx_hal_timebase_tim_template.c, stm32f7xx_hal_timebase_rtc_alarm_template.c and +stm32f7xx_hal_timebase_rtc_wakeup_template.c which override the native HAL time +base functions (defined as weak) to either use the TIM or the RTC as time base tick source. For +more details about the usage of these drivers, please refer to HAL\HAL_TimeBase +examples and FreeRTOS-based applications
  • The following changes done on the HAL drivers require an update on the +application code based on HAL V1.0.4
    • HAL UART, USART, IRDA, SMARTCARD, SPI, I2C, QSPI (referenced as PPP here below) drivers
      • Add PPP error management during DMA process. This requires the following updates on user application:
        • Configure and enable +the PPP IRQ in HAL_PPP_MspInit() function
        • In stm32f7xx_it.c file, +PPP_IRQHandler() +function: add a call to +HAL_PPP_IRQHandler() function +
        • Add and customize +the Error Callback API: HAL_PPP_ErrorCallback()
+
    • HAL I2C (referenced as PPP here below) drivers: +
      • Update to avoid waiting on STOPF/BTF/AF flag under DMA ISR by using the PPP end of transfer interrupt in the DMA transfer process. This requires the following updates on user application:
        • Configure and enable +the PPP IRQ in HAL_PPP_MspInit() function
      +
        • In stm32f7xx_it.c file, +PPP_IRQHandler() +function: add a call to +HAL_PPP_IRQHandler() function
+
    • HAL IWDG driver: rework overall driver for better implementation
      • Remove HAL_IWDG_Start(), HAL_IWDG_MspInit() and HAL_IWDG_GetState() APIs
    • HAL WWDG driver: rework overall driver for better implementation +
      • Remove HAL_WWDG_Start(), HAL_WWDG_Start_IT(), +HAL_WWDG_MspDeInit() and HAL_WWDG_GetState() APIs  +
      • Update the HAL_WWDG_Refresh(WWDG_HandleTypeDef *hwwdg, uint32_t counter)  function and API  by removing the  "counter" parameter
    • HAL QSPI driver:  Enhance the DMA transmit process by using PPP TC interrupt instead of waiting on TC flag under DMA ISR. This requires the following updates on user application:
      • Configure and enable +the QSPI IRQ in HAL_QSPI_MspInit() function
      • In stm32f7xx_it.c file, QSPI_IRQHandler() +function: add a call to +HAL_QSPI_IRQHandler() function
+
    • HAL CEC driver:  Overall driver rework with compatibility break versus previous HAL version
      • Remove HAL CEC polling Process functions: HAL_CEC_Transmit() and HAL_CEC_Receive() +
      • Remove +HAL CEC receive interrupt process function HAL_CEC_Receive_IT() +and enable the "receive"  mode during the Init phase +
      • Rename HAL_CEC_GetReceivedFrameSize() funtion to HAL_CEC_GetLastReceivedFrameSize()
        +
      • Add new HAL APIs: HAL_CEC_SetDeviceAddress() and +HAL_CEC_ChangeRxBuffer() +
      • Remove the 'InitiatorAddress' field from the CEC_InitTypeDef +structure and manage it as a parameter in the HAL_CEC_Transmit_IT() function +
      • Add new parameter 'RxFrameSize' in HAL_CEC_RxCpltCallback() function +
      • Move CEC Rx buffer pointer from CEC_HandleTypeDef structure to +CEC_InitTypeDef structure
  • HAL CAN update 
    • Add the support of CAN3
  • HAL CEC update
    • Overall driver rework with break of compatibility with HAL +V1.0.4
      • Remove the HAL CEC polling Process: HAL_CEC_Transmit() and HAL_CEC_Receive()
+
      • Remove the HAL CEC receive interrupt process (HAL_CEC_Receive_IT()) and manage the "Receive" mode enable within the Init phase +
      • Rename HAL_CEC_GetReceivedFrameSize() function to HAL_CEC_GetLastReceivedFrameSize() function
      • Add new HAL APIs: HAL_CEC_SetDeviceAddress() and +HAL_CEC_ChangeRxBuffer()
      • Remove the 'InitiatorAddress' field from the CEC_InitTypeDef +structure and manage it as a parameter in the HAL_CEC_Transmit_IT() function
      • Add new parameter 'RxFrameSize' in HAL_CEC_RxCpltCallback() function
      • Move CEC Rx buffer pointer from CEC_HandleTypeDef structure to +CEC_InitTypeDef structure
+
    • Update driver to implement the new CEC state machine:
      • Add new "rxState" field in +CEC_HandleTypeDef structure to provide the CEC +state +information related to Rx Operations
      • Rename "state" +field in CEC_HandleTypeDef structure to "gstate": CEC state information +related to global Handle management and Tx Operations +
      • Update CEC process +to manage the new CEC states. +
      • Update __HAL_CEC_RESET_HANDLE_STATE() macro to handle the new CEC +state parameters (gState, rxState)
  • HAL DMA update 
    • Add +new APIs HAL_DMA_RegisterCallback() and HAL_DMA_UnRegisterCallback to +register/unregister the different callbacks identified by +the enum typedef HAL_DMA_CallbackIDTypeDef
    • Add new API HAL_DMA_Abort_IT() to abort DMA transfer under interrupt context
      • The new registered Abort callback is called when DMA transfer abortion is completed
    • Add the check of +compatibility between FIFO threshold level and size of the memory burst in the +HAL_DMA_Init() API +
    • Add new Error Codes: +HAL_DMA_ERROR_PARAM, HAL_DMA_ERROR_NO_XFER and +HAL_DMA_ERROR_NOT_SUPPORTED
    • Remove all DMA states +related to MEM0/MEM1 in HAL_DMA_StateTypeDef
  • HAL DMA2D update 
    • Update the +HAL_DMA2D_DeInit() function to: +
      • Abort transfer in case +of ongoing DMA2D transfer
      +
      • Reset DMA2D control +registers
    • Update +HAL_DMA2D_Abort() to disable DMA2D interrupts after stopping transfer
    • Optimize +HAL_DMA2D_IRQHandler() by reading status registers only once +
    • Update +HAL_DMA2D_ProgramLineEvent() function to: +
      • Return HAL error state +in case of wrong line value
      +
      • Enable line interrupt +after setting the line watermark configuration
    • Add new HAL_DMA2D_CLUTLoad() and HAL_DMA2D_CLUTLoad_IT() +functions to start DMA2D CLUT loading
      • HAL_DMA2D_CLUTLoading_Abort() +function to abort the DMA2D CLUT loading
      • HAL_DMA2D_CLUTLoading_Suspend() +function to suspend the DMA2D CLUT loading
      • HAL_DMA2D_CLUTLoading_Resume() +function to resume the DMA2D CLUT loading
    • Add new DMA2D dead time +management:
      • HAL_DMA2D_EnableDeadTime() +function to enable DMA2D dead time feature
      • HAL_DMA2D_DisableDeadTime() +function to disable DMA2D dead time feature
      • HAL_DMA2D_ConfigDeadTime() +function to configure dead time
    • Update the name of +DMA2D Input/Output color mode defines to be more clear for user (DMA2D_INPUT_XXX +for input layers Colors, DMA2D_OUTPUT_XXX for output framebuffer +Colors)
+ +
  • HAL DCMI update 
    • Rename DCMI_DMAConvCplt +to DCMI_DMAXferCplt +
    • Update HAL_DCMI_Start_DMA() function to Enable the DCMI peripheral +
    • Add new timeout +implementation based on cpu cycles for DCMI stop +
    • Add HAL_DCMI_Suspend() +function to suspend DCMI capture +
    • Add HAL_DCMI_Resume() +function to resume capture after DCMI suspend +
    • Update lock mechanism +for DCMI process +
    • Update HAL_DCMI_IRQHandler() function to: +
      • Add error management in +case DMA errors through XferAbortCallback() and +HAL_DMA_Abort_IT()
      +
      • Optimize code by using +direct register read
    • Move +the content of the stm32f7xx_hal_dcmi_ex.c/.h files to common driver +files (the extension files are kept empty for projects compatibility +reason)
  • HAL FLASH update 
    • Add the support of Dual BANK feature
    • Add __HAL_FLASH_CALC_BOOT_BASE_ADR() macro to calculate the FLASH Boot Base Adress
    • Move Flash total sector define to CMSIS header files
  • HAL FMC update
    • Update FMC_NORSRAM_Init() to remove the Burst access mode configuration
    • Update FMC_SDRAM_Timing_Init() to fix initialization issue when configuring 2 SDRAM banks
  • HAL HCD update
    • Update HCD_Port_IRQHandler() to be compliant with new Time base implementation
  • HAL +I2C update +
    • Add the support of I2C fast mode plus (FM+)
    • Update Polling management:
      • The Timeout value must be estimated for the overall process duration: the Timeout measurement is cumulative
    +
    • Add the management of Abort service: Abort DMA transfer through interrupt
      • In the case of Master Abort IT transfer usage:
        • Add new user HAL_I2C_AbortCpltCallback() to inform user of the end of abort process
        • A new abort state is defined in the HAL_I2C_StateTypeDef structure
    +
    • Add the management of I2C peripheral errors, ACK +failure and STOP condition detection during DMA process. This requires the following updates +on user application:
      • Configure and enable the I2C IRQ in HAL_I2C_MspInit() function
      • In stm32f7xx_it.c file, I2C_IRQHandler() function: add a call to HAL_I2C_IRQHandler() function
      • Add and customize the Error Callback API: HAL_I2C_ErrorCallback()
      • Refer to the I2C_EEPROM or I2C_TwoBoards_ComDMA project examples usage of the API
    • Add the support of I2C repeated start feature: +
      • With the following new APIs
      +
        • HAL_I2C_Master_Sequential_Transmit_IT() +
        • HAL_I2C_Master_Sequential_Receive_IT() +
        • HAL_I2C_Master_Abort_IT() +
        • HAL_I2C_Slave_Sequential_Transmit_IT() +
        • HAL_I2C_Slave_Sequential_Receive_IT() +
        • HAL_I2C_EnableListen_IT() +
        • HAL_I2C_DisableListen_IT()
      +
      • Add new user callbacks:
      +
        • HAL_I2C_ListenCpltCallback()
        • HAL_I2C_AddrCallback()
      +
    • Several +updates on HAL I2C driver to implement the new I2C state machine: +
      • Add new API to get the I2C mode: +HAL_I2C_GetMode() +
      • Update I2C process to +manage the new I2C states
    +
  • HAL IWDG update
    • Overall rework of the driver for a more efficient implementation
      • Remove the following APIs:
        • HAL_IWDG_Start()
        • HAL_IWDG_MspInit()
        • HAL_IWDG_GetState()
      • Update implementation:
        • HAL_IWDG_Init() : this function insures the configuration and the start of the IWDG counter
        • HAL_IWDG_Refresh() : this function insures the reload of the IWDG counter
      • Refer to the following example to identify the changes: IWDG_Example
  • HAL LPTIM update
    • Update HAL_LPTIM_TimeOut_Start_IT() and HAL_LPTIM_Counter_Start_IT( ) APIs +to configure WakeUp Timer EXTI interrupt to be able to wakeup MCU from low power +mode by pressing the EXTI line +
    • Update HAL_LPTIM_TimeOut_Stop_IT() and HAL_LPTIM_Counter_Stop_IT( ) APIs to +disable WakeUp Timer EXTI interrupt
  • HAL LTDC update
    • Update +HAL_LTDC_IRQHandler() to manage the case of reload interrupt
    • Add LTDC extension driver needed with DSI
    • Add HAL_LTDC_SetPitch() function for pitch reconfiguration
    • Add new callback API +HAL_LTDC_ReloadEventCallback() +
    • Add HAL_LTDC_Reload() +to configure LTDC reload feature +
    • Add new No Reload LTDC +variant APIs
      +
      • HAL_LTDC_ConfigLayer_NoReload() +to configure the LTDC Layer according to the specified without reloading +
      • HAL_LTDC_SetWindowSize_NoReload() +to set the LTDC window size without reloading +
      • HAL_LTDC_SetWindowPosition_NoReload() +to set the LTDC window position without reloading +
      • HAL_LTDC_SetPixelFormat_NoReload() +to reconfigure the pixel format without reloading +
      • HAL_LTDC_SetAlpha_NoReload() +to reconfigure the layer alpha value without reloading +
      • HAL_LTDC_SetAddress_NoReload() +to reconfigure the frame buffer Address without reloading +
      • HAL_LTDC_SetPitch_NoReload() +to reconfigure the pitch for specific cases +
      • HAL_LTDC_ConfigColorKeying_NoReload() +to configure the color keying without reloading +
      • HAL_LTDC_EnableColorKeying_NoReload() +to enable the color keying without reloading +
      • HAL_LTDC_DisableColorKeying_NoReload() +to disable the color keying without reloading +
      • HAL_LTDC_EnableCLUT_NoReload() +to enable the color lookup table without reloading +
      • HAL_LTDC_DisableCLUT_NoReload() +to disable the color lookup table without +reloading
      • Note: +Variant functions with “_NoReload” post fix allows to set the LTDC +configuration/settings without immediate reload. This is useful in case +when the program requires to modify several LTDC settings (on one or +both layers) then applying (reload) these settings in one shot by +calling the function “HAL_LTDC_Reload”
+
  • HAL NOR update
    • Update NOR_ADDR_SHIFT macro implementation
  • HAL PCD update
    • Update HAL_PCD_IRQHandler() to get HCLK frequency before setting TRDT value
  • HAL QSPI update
    • Update to manage QSPI error management during DMA process
    • Improve the DMA transmit process by using QSPI TC interrupt instead of waiting loop on TC flag under DMA ISR
    • These two improvements require the following updates on user application:
      • Configure and enable the QSPI IRQ in HAL_QSPI_MspInit() function
      • In stm32f7xx_it.c file, QSPI_IRQHandler() function: add a call to HAL_QSPI_IRQHandler() function
      • Add and customize the Error Callback API: HAL_QSPI_ErrorCallback()
    • Add +the management of non-blocking transfer abort service: HAL_QSPI_Abort_IT(). In +this case the user must:
      • Add new callback HAL_QSPI_AbortCpltCallback() to inform user at the end of abort process
      • A new value of State in the HAL_QSPI_StateTypeDef provides the current state during the abort phase
    • Polling management update:
      • The Timeout value user must be estimated for the overall process duration: the Timeout measurement is cumulative. 
    • Refer to the following examples, which describe the changes:
      • QSPI_ReadWrite_DMA
      • QSPI_MemoryMapped
      • QSPI_ExecuteInPlace
    • Add two new APIs for the QSPI fifo threshold: +
      • HAL_QSPI_SetFifoThreshold(): configure the FIFO threshold of +the QSPI +
      • HAL_QSPI_GetFifoThreshold(): give the current FIFO +threshold
      +
    • Fix wrong data size management in HAL_QSPI_Receive_DMA()
  • HAL RCC update
    • Update HAL_RCC_PeriphCLKConfig() function to adjust the SystemCoreClock
    • Optimize HAL_RCC_ClockConfig() function code
    • Optimize internal oscillators and PLL startup times
  • HAL RTC update 
    • Update HAL_RTC_GetTime() with proper 'SubSeconds' and 'SecondFraction' management
  • HAL SAI update 
    • Update SAI state in case of TIMEOUT error within the HAL_SAI_Transmit() / HAL_SAI_Receive() +
    • Update HAL_SAI_IRQHandler: +
      • Add error management in +case DMA errors through XferAbortCallback() and HAL_DMA_Abort_IT() +
      • Add error management in +case of IT
    • Move +SAI_BlockSynchroConfig() and SAI_GetInputClock() functions to +stm32f7xx_hal_sai.c/.h files (extension files are kept empty for +projects compatibility reason)
+
  • HAL SPDIFRX update
    • Overall driver update for wait on flag management optimization
  • HAL SPI update
    • Overall driver optimization to improve performance in polling/interrupt mode to reach maximum peripheral frequency
      • Polling mode: +
        • Replace the use of SPI_WaitOnFlagUnitTimeout() function by "if" +statement to check on RXNE/TXE flage while transferring +data
+
      •  Interrupt mode:
        • Minimize access on SPI registers +
      • All modes:
        • Add the USE_SPI_CRC switch to minimize the number of statements when CRC calculation is disabled
        • Update timeout management to check on global processes
        • Update error code management in all processes
    • Update DMA process: +
      • Add the management of SPI peripheral errors during DMA process. This requires the following updates in +the user application:
        • Configure and enable the SPI IRQ in HAL_SPI_MspInit() function
        • In stm32f7xx_it.c file, SPI_IRQHandler() function: add a call to HAL_SPI_IRQHandler() function
        • Add and customize the Error Callback API: HAL_SPI_ErrorCallback()
        • Refer to the following example which describe the changes: SPI_FullDuplex_ComDMA
      +
  • HAL TIM update 
    • Update HAL_TIM_ConfigOCrefClear() function for proper configuration of the SMCR register
    • Add new function HAL_TIMEx_ConfigBreakInput() to configure the break input source
  • HAL UART, USART, SMARTCARD and IRDA (referenced as PPP here below) update +
    • Update Polling management:
      • The user Timeout value must be estimated for the overall process duration: the Timeout measurement is cumulative
    • Update DMA process:
      • Update the management of PPP peripheral errors during DMA process. This requires the following updates in user application:
        • Configure and enable the PPP IRQ in HAL_PPP_MspInit() function
        • In stm32f7xx_it.c file, PPP_IRQHandler() function: add a call to HAL_PPP_IRQHandler() function
        • Add and customize the Error Callback API: HAL_PPP_ErrorCallback()
  • HAL WWDG update 
    • Overall rework of the driver for more efficient implementation
      • Remove the following APIs:
        • HAL_WWDG_Start()
        • HAL_WWDG_Start_IT()
        • HAL_WWDG_MspDeInit()
        • HAL_WWDG_GetState()
      • Update implementation:
        • HAL_WWDG_Init()
          • A new parameter in the Init Structure: EWIMode
        • HAL_WWDG_MspInit()
        • HAL_WWDG_Refresh() 
          • This function insures the reload of the counter
          • The "counter" parameter has been removed
        • HAL_WWDG_IRQHandler()
        • HAL_WWDG_EarlyWakeupCallback() is the new prototype of HAL_WWDG_WakeupCallback()
    • Refer to the following example to identify the changes: WWDG_Example

V1.0.4 / 09-December-2015

+

Main +Changes

  • HAL Generic update
    • Update HAL +weak empty callbacks to prevent unused argument compilation warnings with some +compilers by calling the following line: +
      • UNUSED(hppp);
  • HAL ETH update 
    • Update HAL_ETH_Init() function to add timeout on the Software reset management

V1.0.3 / 13-November-2015

+

Main +Changes

  • General updates +to fix known defects and enhancements implementation
  • One change done on the HAL CRYP requires an update on +the application code based on HAL V1.0.2 +
    • Update +HAL_CRYP_DESECB_Decrypt() API to invert pPlainData and pCypherData +parameters
  • HAL Generic update
    • Update HAL +weak empty callbacks to prevent unused argument compilation warnings with some +compilers by calling the following line: +
      • UNUSED(hppp);
    • Remove references to STM32CubeMX and MicroXplorer from stm32f7xx_hal_msp_template.c file
  • HAL ADC update
    • Replace ADC_CHANNEL_TEMPSENSOR definition from ADC_CHANNEL_16 to ADC_CHANNEL_18  
    • Update HAL ADC driver state machine for code efficiency
    • Add new literal: ADC_INJECTED_SOFTWARE_START to be used as possible +value for the ExternalTrigInjecConvEdge parameter in the ADC_InitTypeDef +structure to select the ADC software trigger mode.
  • HAL CORTEX update +
    • Remove duplication +for __HAL_CORTEX_SYSTICKCLK_CONFIG() macro
  • HAL CRYP update
    • Update HAL_CRYP_DESECB_Decrypt() API to fix the inverted pPlainData and pCypherData parameters issue
  • HAL FLASH update
    • Update OB_IWDG_STOP_ACTIVE definition
    • Update OB_RDP_LEVEL_x definition by proper values
    • Update FLASH_MassErase() function to consider the voltage range parameter in the mass erase configuration
  • HAL RCC update
    • update values for LSE Drive capability defines
    • update PLLN min value 50 instead of 100
    • add RCC_PLLI2SP_DIVx defines for PLLI2SP clock divider
    • Update __HAL_RCC_USB_OTG_FS_CLK_DISABLE() macro to remove the disable of the SYSCFG 
    • Update HAL_RCCEx_GetPeriphCLKFreq() function for proper SAI clock configuration
  • HAL SAI update
    • update for proper management of the external synchronization input selection
      • update of HAL_SAI_Init () funciton
      • update definition of SAI_Block_SyncExt and SAI_Block_Synchronization groups
    • update SAI_SLOTACTIVE_X  defines values
    • update HAL_SAI_Init() function for proper companding mode management
    • update SAI_Transmit_ITxxBit() functions to add the check on transfer counter before writing new data to SAIx_DR registers
    • update SAI_FillFifo() function to avoid issue when the number of data to transmit is smaller than the FIFO size
    • update HAL_SAI_EnableRxMuteMode() function for proper mute management
    • update SAI_InitPCM() function to support 24bits configuration
  • HAL SD update
    • update HAL_SD_Get_CardInfo() to properly support high capacity cards
  • HAL SPDIFRX update
    • update SPDIFRX_DMARxCplt() function implementation to check on circular mode before disabling the DMA
  • HAL TIM update
    • Update HAL_TIM_ConfigClockSource() function implementation for proper parameters check
  • HAL UART update
    • Update __HAL_UART_CLEAR_IT macro for proper functionning 
  • ll FMC update
    • add FMC_PAGE_SIZE_512 define
  • ll SDMMC update
    • update SDMMC_SetSDMMCReadWaitMode() function for proper functionning

V1.0.2 / 21-September-2015

+

Main +Changes

  • HAL Generic update
    • stm32f7xx_hal.conf_template.h: update HSE_STARTUP_TIMEOUT
    • stm32f7xx_hal_def.h: update the quotation marks used in #error"USE_RTOS should be 0 in the current HAL release"
  • HAL DMA update
    • Overall +driver update for code optimization
      • add +StreamBaseAddress and StreamIndex new fields in the DMA_HandleTypeDef +structure +
      • add +DMA_Base_Registers private structure +
      • add static function +DMA_CalcBaseAndBitshift() +
      • update +HAL_DMA_Init() function to use the new added static function +
      • update +HAL_DMA_DeInit() function to optimize clear flag operations +
      • update +HAL_DMA_Start_IT() function to optimize interrupts enable +
      • update +HAL_DMA_PollForTransfer() function to optimize check on flags +
      • update +HAL_DMA_IRQHandler() function to optimize interrupt flag management
  • HAL ETH update
    • remove duplicated macro IS_ETH_RX_MODE()
  • HAL GPIO update
    • Rename +GPIO_SPEED_LOW define to GPIO_SPEED_FREQ_LOW +
    • Rename +GPIO_SPEED_MEDIUM define to GPIO_SPEED_FREQ_MEDIUM +
    • Rename +GPIO_SPEED_FAST define to GPIO_SPEED_FREQ_HIGH +
    • Rename +GPIO_SPEED_HIGH define to GPIO_SPEED_FREQ_VERY_HIGH
  • HAL HASH update
    • Rename +HAL_HASH_STATETypeDef to HAL_HASH_StateTypeDef +
    • Rename +HAL_HASH_PhaseTypeDef to HAL_HASHPhaseTypeDef
  • HAL RCC update
    • update values for LSE Drive capability defines
    • update PLLN/PLLI2SN/PLLSAI VCO min value 100MHz instead of 192MHz
    • add __HAL_RCC_MCO1_CONFIG() and __HAL_RCC_MCO2_CONFIG() macros
    • update HAL_RCCEx_PeriphCLKConfig() function to reset the Backup domain only if the RTC Clock source selection is modified 
  • HAL TIM update
    • update the implementation of __HAL_TIM_SET_COMPARE() macro
    • remove useless assert() in HAL_TIM_PWM_ConfigChannel(), TIM_OC2_SetConfig() and HAL_TIM_PWM_ConfigChannel() functions
  • HAL CAN update
    • add the clear flag ERRI bit in HAL_CAN_IRQHandler()
  • HAL I2S update
    • update I2S HAL_I2S_Transmit() API to keep the check on busy flag only for the slave
  • HAL QSPI update
    • Add __HAL_QSPI_CLEAR_FLAG() before QSPI_Config()
  • HAL UART update
    • Remove +enabling of ERR IT source and PE source from HAL_UART_Transmit_IT() and +remove the corresponding disabling ERR/PE IT from UART_EndTransmit_IT()
  • HAL PCD update 
    • Clean status phase received interrupt when DMA mode enabled 
  • HAL HCD update
    • Update to use local +variable in USB Host channel re-activation
  • ll FMC update
    • update the define FMC Write FIFO Disable/Enable: FMC_WRITE_FIFO_DISABLE and FMC_WRITE_FIFO_ENABLE
    • remove return HAL_ERROR from FMC_SDRAM_SendCommand() function

V1.0.1 / 25-June-2015

+

Main +Changes

  • General updates +to fix known defects and enhancements implementation
  • HAL CRC update
    • update __HAL_CRC_SET_IDR() macro implementation to use WRITE_REG() instead of MODIFY_REG()
  • HAL CEC update
    • update timeout management in HAL_CEC_Transmit() and HAL_CEC_Receive() functions
  • HAL Cortex update
    • update HAL_MPU_ConfigRegion() function to be misra compliant
  • HAL ETH update
    • Remove +duplicated IS_ETH_DUPLEX_MODE() and IS_ETH_RX_MODE() macros
    • Remove +illegal space ETH_MAC_READCONTROLLER_FLUSHING macro
    • Update +ETH_MAC_READCONTROLLER_XXX defined values (XXX can be IDLE, READING_DATA and +READING_STATUS)
  • HAL FLASH update
    • update FLASH_OB_GetRDP() function to return uint8_t  instead of FlagStatus
    • update OB_RDP_LEVELx definition
    • add __HAL_FLASH_GET_LATENCY() macro
  • HAL HASH update
    • update +HASH_DMAXferCplt() and HASHEx_DMAXferCplt() functions to properly +configure the number of valid bits in last word of the message
    • update HAL_HASH_SHA1_Accumulate() function to check on the length of the input buffer
    • update +HAL_HASH_MODE_Start_IT() functions (Mode stands for MD5, SHA1, SHA224 and SHA256 ) to :
      • Fix processing +fail for small input buffers +
      • to unlock +the process and call return HAL_OK at the end of HASH processing to avoid +incorrect repeating software +
      • properly to manage +the HashITCounter efficiency +
      • Update to call the +HAL_HASH_InCpltCallback() at the end of the complete buffer instead +of +every each 512 bits
    • update HASH_IT_DINI and HASH_IT_DCI definition
    • update __HAL_HASH_GET_FLAG() macro definition
  • HAL I2S update
    • update HAL_I2S_Transmit() function to ensure the waiting on Busy flag in case of slave mode selection
  • HAL RTC update
    • update HAL_RTCEx_SetWakeUpTimer() and HAL_RTCEx_SetWakeUpTimer_IT() functions to properly check on WUTWF flag
    • rename RTC_TIMESTAMPPIN_PI8 define to RTC_TIMESTAMPPIN_POS1
    • rename RTC_TIMESTAMPPIN_PC1 define to RTC_TIMESTAMPPIN_POS2
    • update __HAL_RTC_WAKEUPTIMER_CLEAR_FLAG() macro definition
    • update __HAL_RTC_TAMPER_GET_IT() macro definition
    • update __HAL_RTC_TAMPER_CLEAR_FLAG() macro definition
    • update __HAL_RTC_TIMESTAMP_CLEAR_FLAG() macro definition
    • update __HAL_RTC_TAMPER_TIMESTAMP_EXTI_GET_FLAG() macro definition
    • add RTC_TAMPCR_TAMPXE and RTC_TAMPCR_TAMPXIE defines
  • HAL SMARTCARD update
    • add SMARTCARD_FLAG_IDLE, SMARTCARD_IT_IDLE and  SMARTCARD_CLEAR_IDLEF defines
  • HAL UART update
    • update HAL_UART_DMAResume() function to clear overrun flag before resuming the Rx transfer
    • update UART_FLAG_SBKF definition
  • HAL USART update
    • update HAL_USART_DMAResume() function to clear overrun flag before resuming the Rx transfer
  • LL FMC update
    • update NAND timing maximum values
  • LL USB update +
    • USB_FlushTxFifo API: +update to flush all Tx FIFO +
    • Update to use local +variable in USB Host channel re-activation
+ +

V1.0.0 / 12-May-2015

+

Main +Changes

  • First official release for STM32F756xx/746xx/745xx +devices
+ +

License

+
+
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. +
  3. 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.
  4. +
  5. Neither the +name of STMicroelectronics nor the names of its contributors may be +used to endorse or promote products derived
    +
  6. +
+       +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.
+
+ +
+
+

For +complete documentation on STM32 Microcontrollers visit www.st.com/STM32

+
+

+
+
+

 

+
\ No newline at end of file diff --git a/lib/main/STM32F7xx_HAL_Driver/STM32F745xx_User_Manual.chm b/lib/main/STM32F7xx_HAL_Driver/STM32F745xx_User_Manual.chm deleted file mode 100644 index 68e446935d..0000000000 Binary files a/lib/main/STM32F7xx_HAL_Driver/STM32F745xx_User_Manual.chm and /dev/null differ diff --git a/lib/main/STM32F7xx_HAL_Driver/STM32F746xx_User_Manual.chm b/lib/main/STM32F7xx_HAL_Driver/STM32F746xx_User_Manual.chm deleted file mode 100644 index 1f135740cf..0000000000 Binary files a/lib/main/STM32F7xx_HAL_Driver/STM32F746xx_User_Manual.chm and /dev/null differ diff --git a/lib/main/STM32F7xx_HAL_Driver/STM32F756xx_User_Manual.chm b/lib/main/STM32F7xx_HAL_Driver/STM32F756xx_User_Manual.chm deleted file mode 100644 index 212febfeb3..0000000000 Binary files a/lib/main/STM32F7xx_HAL_Driver/STM32F756xx_User_Manual.chm and /dev/null differ diff --git a/lib/main/STM32F7xx_HAL_Driver/STM32F779xx_User_Manual.chm b/lib/main/STM32F7xx_HAL_Driver/STM32F779xx_User_Manual.chm deleted file mode 100644 index f55ffa7c4c..0000000000 Binary files a/lib/main/STM32F7xx_HAL_Driver/STM32F779xx_User_Manual.chm and /dev/null differ