Latest F7 HAL drivers (preparing for F722RE)

This commit is contained in:
blckmn 2017-01-03 14:47:24 +11:00
parent 0cf4feaf1d
commit 7b62b9a7ef
65 changed files with 2467 additions and 2431 deletions

View File

@ -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 /*!<Threshold LOW */
#define SPDIFRX_DIR_TLO 0x1FFF0000U /*!<Threshold HIGH */
/******************************************************************************/
/* */
/* SD host Interface */
@ -8766,6 +8765,7 @@ typedef struct
/**
* @}
*/
@ -8819,28 +8819,28 @@ typedef struct
/******************************* GPIO Instances *******************************/
#define IS_GPIO_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == GPIOA) || \
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
#define IS_GPIO_AF_INSTANCE(__INSTANCE__) (((__INSTANCE__) == GPIOA) || \
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
/****************************** CEC Instances *********************************/
#define IS_CEC_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == CEC)
@ -8851,14 +8851,14 @@ typedef struct
/******************************** I2C Instances *******************************/
#define IS_I2C_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == I2C1) || \
((__INSTANCE__) == I2C2) || \
((__INSTANCE__) == I2C3) || \
((__INSTANCE__) == I2C4))
((__INSTANCE__) == I2C2) || \
((__INSTANCE__) == I2C3) || \
((__INSTANCE__) == I2C4))
/******************************** I2S Instances *******************************/
#define IS_I2S_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == SPI1) || \
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3))
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3))
/******************************* LPTIM Instances ********************************/
#define IS_LPTIM_INSTANCE(__INSTANCE__) ((__INSTANCE__) == LPTIM1)
@ -8866,6 +8866,7 @@ typedef struct
/******************************* RNG Instances ********************************/
#define IS_RNG_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == RNG)
@ -8888,11 +8889,11 @@ typedef struct
/******************************** SPI Instances *******************************/
#define IS_SPI_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == SPI1) || \
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3) || \
((__INSTANCE__) == SPI4) || \
((__INSTANCE__) == SPI5) || \
((__INSTANCE__) == SPI6))
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3) || \
((__INSTANCE__) == SPI4) || \
((__INSTANCE__) == SPI5) || \
((__INSTANCE__) == SPI6))
/****************** TIM Instances : All supported instances *******************/
#define IS_TIM_INSTANCE(__INSTANCE__) (((__INSTANCE__) == TIM1) || \

View File

@ -2,8 +2,8 @@
******************************************************************************
* @file stm32f746xx.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:
@ -314,7 +314,6 @@ typedef struct
__IO uint32_t IER; /*!< CEC interrupt enable register, Address offset:0x14 */
}CEC_TypeDef;
/**
* @brief CRC calculation unit
*/
@ -407,7 +406,6 @@ typedef struct
__IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */
} DMA_TypeDef;
/**
* @brief DMA2D Controller
*/
@ -854,7 +852,6 @@ typedef struct
__IO uint32_t DIR; /*!< Debug Information register, Address offset: 0x18 */
} SPDIFRX_TypeDef;
/**
* @brief SD host Interface
*/
@ -1322,7 +1319,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)
@ -3667,7 +3664,6 @@ typedef struct
/******************** Bit definition for DMA2D_BGCLUT register **************/
/******************************************************************************/
/* */
/* External Interrupt/Event Controller */
@ -3977,6 +3973,7 @@ typedef struct
#define FLASH_OPTCR1_BOOT_ADD0 0x0000FFFFU
#define FLASH_OPTCR1_BOOT_ADD1 0xFFFF0000U
/******************************************************************************/
/* */
/* Flexible Memory Controller */
@ -6044,7 +6041,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
@ -6064,6 +6061,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
@ -6639,7 +6639,6 @@ typedef struct
#define SPDIFRX_DIR_THI 0x000013FFU /*!<Threshold LOW */
#define SPDIFRX_DIR_TLO 0x1FFF0000U /*!<Threshold HIGH */
/******************************************************************************/
/* */
/* SD host Interface */
@ -8974,6 +8973,7 @@ typedef struct
/**
* @}
*/
@ -9027,28 +9027,28 @@ typedef struct
/******************************* GPIO Instances *******************************/
#define IS_GPIO_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == GPIOA) || \
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
#define IS_GPIO_AF_INSTANCE(__INSTANCE__) (((__INSTANCE__) == GPIOA) || \
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
/****************************** CEC Instances *********************************/
#define IS_CEC_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == CEC)
@ -9059,14 +9059,14 @@ typedef struct
/******************************** I2C Instances *******************************/
#define IS_I2C_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == I2C1) || \
((__INSTANCE__) == I2C2) || \
((__INSTANCE__) == I2C3) || \
((__INSTANCE__) == I2C4))
((__INSTANCE__) == I2C2) || \
((__INSTANCE__) == I2C3) || \
((__INSTANCE__) == I2C4))
/******************************** I2S Instances *******************************/
#define IS_I2S_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == SPI1) || \
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3))
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3))
/******************************* LPTIM Instances ********************************/
#define IS_LPTIM_INSTANCE(__INSTANCE__) ((__INSTANCE__) == LPTIM1)
@ -9076,6 +9076,7 @@ typedef struct
/******************************* RNG Instances ********************************/
#define IS_RNG_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == RNG)
@ -9098,11 +9099,11 @@ typedef struct
/******************************** SPI Instances *******************************/
#define IS_SPI_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == SPI1) || \
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3) || \
((__INSTANCE__) == SPI4) || \
((__INSTANCE__) == SPI5) || \
((__INSTANCE__) == SPI6))
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3) || \
((__INSTANCE__) == SPI4) || \
((__INSTANCE__) == SPI5) || \
((__INSTANCE__) == SPI6))
/****************** TIM Instances : All supported instances *******************/
#define IS_TIM_INSTANCE(__INSTANCE__) (((__INSTANCE__) == TIM1) || \

View File

@ -2,8 +2,8 @@
******************************************************************************
* @file stm32f756xx.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:
@ -315,7 +315,6 @@ typedef struct
__IO uint32_t IER; /*!< CEC interrupt enable register, Address offset:0x14 */
}CEC_TypeDef;
/**
* @brief CRC calculation unit
*/
@ -408,7 +407,6 @@ typedef struct
__IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */
} DMA_TypeDef;
/**
* @brief DMA2D Controller
*/
@ -855,7 +853,6 @@ typedef struct
__IO uint32_t DIR; /*!< Debug Information register, Address offset: 0x18 */
} SPDIFRX_TypeDef;
/**
* @brief SD host Interface
*/
@ -1394,7 +1391,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)
@ -3795,7 +3792,6 @@ typedef struct
/******************** Bit definition for DMA2D_BGCLUT register **************/
/******************************************************************************/
/* */
/* External Interrupt/Event Controller */
@ -4105,6 +4101,7 @@ typedef struct
#define FLASH_OPTCR1_BOOT_ADD0 0x0000FFFFU
#define FLASH_OPTCR1_BOOT_ADD1 0xFFFF0000U
/******************************************************************************/
/* */
/* Flexible Memory Controller */
@ -6231,7 +6228,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
@ -6251,6 +6248,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
@ -6826,7 +6826,6 @@ typedef struct
#define SPDIFRX_DIR_THI 0x000013FFU /*!<Threshold LOW */
#define SPDIFRX_DIR_TLO 0x1FFF0000U /*!<Threshold HIGH */
/******************************************************************************/
/* */
/* SD host Interface */
@ -9161,6 +9160,7 @@ typedef struct
/**
* @}
*/
@ -9214,28 +9214,28 @@ typedef struct
/******************************* GPIO Instances *******************************/
#define IS_GPIO_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == GPIOA) || \
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
#define IS_GPIO_AF_INSTANCE(__INSTANCE__) (((__INSTANCE__) == GPIOA) || \
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
/****************************** CEC Instances *********************************/
#define IS_CEC_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == CEC)
@ -9246,14 +9246,14 @@ typedef struct
/******************************** I2C Instances *******************************/
#define IS_I2C_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == I2C1) || \
((__INSTANCE__) == I2C2) || \
((__INSTANCE__) == I2C3) || \
((__INSTANCE__) == I2C4))
((__INSTANCE__) == I2C2) || \
((__INSTANCE__) == I2C3) || \
((__INSTANCE__) == I2C4))
/******************************** I2S Instances *******************************/
#define IS_I2S_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == SPI1) || \
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3))
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3))
/******************************* LPTIM Instances ********************************/
#define IS_LPTIM_INSTANCE(__INSTANCE__) ((__INSTANCE__) == LPTIM1)
@ -9263,6 +9263,7 @@ typedef struct
/******************************* RNG Instances ********************************/
#define IS_RNG_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == RNG)
@ -9285,11 +9286,11 @@ typedef struct
/******************************** SPI Instances *******************************/
#define IS_SPI_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == SPI1) || \
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3) || \
((__INSTANCE__) == SPI4) || \
((__INSTANCE__) == SPI5) || \
((__INSTANCE__) == SPI6))
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3) || \
((__INSTANCE__) == SPI4) || \
((__INSTANCE__) == SPI5) || \
((__INSTANCE__) == SPI6))
/****************** TIM Instances : All supported instances *******************/
#define IS_TIM_INSTANCE(__INSTANCE__) (((__INSTANCE__) == TIM1) || \

View File

@ -2,8 +2,8 @@
******************************************************************************
* @file stm32f765xx.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:
@ -322,7 +322,6 @@ typedef struct
__IO uint32_t IER; /*!< CEC interrupt enable register, Address offset:0x14 */
}CEC_TypeDef;
/**
* @brief CRC calculation unit
*/
@ -449,7 +448,6 @@ typedef struct
__IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */
} DMA_TypeDef;
/**
* @brief DMA2D Controller
*/
@ -850,7 +848,6 @@ typedef struct
__IO uint32_t DIR; /*!< Debug Information register, Address offset: 0x18 */
} SPDIFRX_TypeDef;
/**
* @brief SD host Interface
*/
@ -1412,7 +1409,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)
@ -3913,7 +3910,6 @@ typedef struct
/******************** Bit definition for DMA2D_BGCLUT register **************/
/******************************************************************************/
/* */
/* External Interrupt/Event Controller */
@ -4240,6 +4236,7 @@ typedef struct
#define FLASH_OPTCR1_BOOT_ADD0 0x0000FFFFU
#define FLASH_OPTCR1_BOOT_ADD1 0xFFFF0000U
/******************************************************************************/
/* */
/* Flexible Memory Controller */
@ -6169,7 +6166,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
@ -6189,6 +6186,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
@ -6760,7 +6760,6 @@ typedef struct
#define SPDIFRX_DIR_THI 0x000013FFU /*!<Threshold LOW */
#define SPDIFRX_DIR_TLO 0x1FFF0000U /*!<Threshold HIGH */
/******************************************************************************/
/* */
/* SD host Interface */
@ -9101,6 +9100,7 @@ typedef struct
#define USB_OTG_PCGCCTL_PHYSUSP 0x00000010U /*!<Bit 1 */
/******************************************************************************/
/* */
/* MDIOS */
@ -9209,28 +9209,28 @@ typedef struct
/******************************* GPIO Instances *******************************/
#define IS_GPIO_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == GPIOA) || \
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
#define IS_GPIO_AF_INSTANCE(__INSTANCE__) (((__INSTANCE__) == GPIOA) || \
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
/****************************** CEC Instances *********************************/
#define IS_CEC_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == CEC)
@ -9241,14 +9241,14 @@ typedef struct
/******************************** I2C Instances *******************************/
#define IS_I2C_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == I2C1) || \
((__INSTANCE__) == I2C2) || \
((__INSTANCE__) == I2C3) || \
((__INSTANCE__) == I2C4))
((__INSTANCE__) == I2C2) || \
((__INSTANCE__) == I2C3) || \
((__INSTANCE__) == I2C4))
/******************************** I2S Instances *******************************/
#define IS_I2S_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == SPI1) || \
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3))
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3))
/******************************* LPTIM Instances ********************************/
#define IS_LPTIM_INSTANCE(__INSTANCE__) ((__INSTANCE__) == LPTIM1)
@ -9258,6 +9258,7 @@ typedef struct
#define IS_MDIOS_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == MDIOS)
/******************************* RNG Instances ********************************/
#define IS_RNG_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == RNG)
@ -9281,11 +9282,11 @@ typedef struct
/******************************** SPI Instances *******************************/
#define IS_SPI_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == SPI1) || \
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3) || \
((__INSTANCE__) == SPI4) || \
((__INSTANCE__) == SPI5) || \
((__INSTANCE__) == SPI6))
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3) || \
((__INSTANCE__) == SPI4) || \
((__INSTANCE__) == SPI5) || \
((__INSTANCE__) == SPI6))
/****************** TIM Instances : All supported instances *******************/
#define IS_TIM_INSTANCE(__INSTANCE__) (((__INSTANCE__) == TIM1) || \

View File

@ -2,8 +2,8 @@
******************************************************************************
* @file stm32f767xx.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:
@ -325,7 +325,6 @@ typedef struct
__IO uint32_t IER; /*!< CEC interrupt enable register, Address offset:0x14 */
}CEC_TypeDef;
/**
* @brief CRC calculation unit
*/
@ -452,7 +451,6 @@ typedef struct
__IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */
} DMA_TypeDef;
/**
* @brief DMA2D Controller
*/
@ -900,7 +898,6 @@ typedef struct
__IO uint32_t DIR; /*!< Debug Information register, Address offset: 0x18 */
} SPDIFRX_TypeDef;
/**
* @brief SD host Interface
*/
@ -1502,7 +1499,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)
@ -4007,7 +4004,6 @@ typedef struct
/******************** Bit definition for DMA2D_BGCLUT register **************/
/******************************************************************************/
/* */
/* External Interrupt/Event Controller */
@ -4334,6 +4330,7 @@ typedef struct
#define FLASH_OPTCR1_BOOT_ADD0 0x0000FFFFU
#define FLASH_OPTCR1_BOOT_ADD1 0xFFFF0000U
/******************************************************************************/
/* */
/* Flexible Memory Controller */
@ -6417,7 +6414,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
@ -6437,6 +6434,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
@ -7008,7 +7008,6 @@ typedef struct
#define SPDIFRX_DIR_THI 0x000013FFU /*!<Threshold LOW */
#define SPDIFRX_DIR_TLO 0x1FFF0000U /*!<Threshold HIGH */
/******************************************************************************/
/* */
/* SD host Interface */
@ -9348,6 +9347,7 @@ typedef struct
#define USB_OTG_PCGCCTL_GATECLK 0x00000002U /*!<Bit 0 */
#define USB_OTG_PCGCCTL_PHYSUSP 0x00000010U /*!<Bit 1 */
/******************************************************************************/
/* */
/* JPEG Encoder/Decoder */
@ -9606,28 +9606,28 @@ typedef struct
/******************************* GPIO Instances *******************************/
#define IS_GPIO_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == GPIOA) || \
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
#define IS_GPIO_AF_INSTANCE(__INSTANCE__) (((__INSTANCE__) == GPIOA) || \
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
/****************************** CEC Instances *********************************/
#define IS_CEC_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == CEC)
@ -9638,14 +9638,14 @@ typedef struct
/******************************** I2C Instances *******************************/
#define IS_I2C_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == I2C1) || \
((__INSTANCE__) == I2C2) || \
((__INSTANCE__) == I2C3) || \
((__INSTANCE__) == I2C4))
((__INSTANCE__) == I2C2) || \
((__INSTANCE__) == I2C3) || \
((__INSTANCE__) == I2C4))
/******************************** I2S Instances *******************************/
#define IS_I2S_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == SPI1) || \
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3))
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3))
/******************************* LPTIM Instances ********************************/
#define IS_LPTIM_INSTANCE(__INSTANCE__) ((__INSTANCE__) == LPTIM1)
@ -9659,6 +9659,7 @@ typedef struct
/****************************** MDIOS Instances ********************************/
#define IS_JPEG_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == JPEG)
/******************************* RNG Instances ********************************/
#define IS_RNG_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == RNG)
@ -9682,11 +9683,11 @@ typedef struct
/******************************** SPI Instances *******************************/
#define IS_SPI_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == SPI1) || \
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3) || \
((__INSTANCE__) == SPI4) || \
((__INSTANCE__) == SPI5) || \
((__INSTANCE__) == SPI6))
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3) || \
((__INSTANCE__) == SPI4) || \
((__INSTANCE__) == SPI5) || \
((__INSTANCE__) == SPI6))
/****************** TIM Instances : All supported instances *******************/
#define IS_TIM_INSTANCE(__INSTANCE__) (((__INSTANCE__) == TIM1) || \

View File

@ -2,8 +2,8 @@
******************************************************************************
* @file stm32f769xx.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:
@ -326,7 +326,6 @@ typedef struct
__IO uint32_t IER; /*!< CEC interrupt enable register, Address offset:0x14 */
}CEC_TypeDef;
/**
* @brief CRC calculation unit
*/
@ -453,7 +452,6 @@ typedef struct
__IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */
} DMA_TypeDef;
/**
* @brief DMA2D Controller
*/
@ -901,7 +899,6 @@ typedef struct
__IO uint32_t DIR; /*!< Debug Information register, Address offset: 0x18 */
} SPDIFRX_TypeDef;
/**
* @brief SD host Interface
*/
@ -1584,7 +1581,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)
@ -4090,7 +4087,6 @@ typedef struct
/******************** Bit definition for DMA2D_BGCLUT register **************/
/******************************************************************************/
/* */
/* External Interrupt/Event Controller */
@ -4417,6 +4413,7 @@ typedef struct
#define FLASH_OPTCR1_BOOT_ADD0 0x0000FFFFU
#define FLASH_OPTCR1_BOOT_ADD1 0xFFFF0000U
/******************************************************************************/
/* */
/* Flexible Memory Controller */
@ -6504,7 +6501,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
@ -6524,6 +6521,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
@ -7095,7 +7095,6 @@ typedef struct
#define SPDIFRX_DIR_THI 0x000013FFU /*!<Threshold LOW */
#define SPDIFRX_DIR_TLO 0x1FFF0000U /*!<Threshold HIGH */
/******************************************************************************/
/* */
/* SD host Interface */
@ -9435,6 +9434,7 @@ typedef struct
#define USB_OTG_PCGCCTL_GATECLK 0x00000002U /*!<Bit 0 */
#define USB_OTG_PCGCCTL_PHYSUSP 0x00000010U /*!<Bit 1 */
/******************************************************************************/
/* */
/* JPEG Encoder/Decoder */
@ -10882,28 +10882,28 @@ typedef struct
/******************************* GPIO Instances *******************************/
#define IS_GPIO_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == GPIOA) || \
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
#define IS_GPIO_AF_INSTANCE(__INSTANCE__) (((__INSTANCE__) == GPIOA) || \
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
/****************************** CEC Instances *********************************/
#define IS_CEC_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == CEC)
@ -10914,14 +10914,14 @@ typedef struct
/******************************** I2C Instances *******************************/
#define IS_I2C_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == I2C1) || \
((__INSTANCE__) == I2C2) || \
((__INSTANCE__) == I2C3) || \
((__INSTANCE__) == I2C4))
((__INSTANCE__) == I2C2) || \
((__INSTANCE__) == I2C3) || \
((__INSTANCE__) == I2C4))
/******************************** I2S Instances *******************************/
#define IS_I2S_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == SPI1) || \
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3))
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3))
/******************************* LPTIM Instances ********************************/
#define IS_LPTIM_INSTANCE(__INSTANCE__) ((__INSTANCE__) == LPTIM1)
@ -10935,6 +10935,7 @@ typedef struct
/****************************** MDIOS Instances ********************************/
#define IS_JPEG_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == JPEG)
/******************************* RNG Instances ********************************/
#define IS_RNG_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == RNG)
@ -10958,11 +10959,11 @@ typedef struct
/******************************** SPI Instances *******************************/
#define IS_SPI_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == SPI1) || \
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3) || \
((__INSTANCE__) == SPI4) || \
((__INSTANCE__) == SPI5) || \
((__INSTANCE__) == SPI6))
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3) || \
((__INSTANCE__) == SPI4) || \
((__INSTANCE__) == SPI5) || \
((__INSTANCE__) == SPI6))
/****************** TIM Instances : All supported instances *******************/
#define IS_TIM_INSTANCE(__INSTANCE__) (((__INSTANCE__) == TIM1) || \

View File

@ -2,8 +2,8 @@
******************************************************************************
* @file stm32f777xx.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:
@ -326,7 +326,6 @@ typedef struct
__IO uint32_t IER; /*!< CEC interrupt enable register, Address offset:0x14 */
}CEC_TypeDef;
/**
* @brief CRC calculation unit
*/
@ -453,7 +452,6 @@ typedef struct
__IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */
} DMA_TypeDef;
/**
* @brief DMA2D Controller
*/
@ -901,7 +899,6 @@ typedef struct
__IO uint32_t DIR; /*!< Debug Information register, Address offset: 0x18 */
} SPDIFRX_TypeDef;
/**
* @brief SD host Interface
*/
@ -1574,7 +1571,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)
@ -4135,7 +4132,6 @@ typedef struct
/******************** Bit definition for DMA2D_BGCLUT register **************/
/******************************************************************************/
/* */
/* External Interrupt/Event Controller */
@ -4462,6 +4458,7 @@ typedef struct
#define FLASH_OPTCR1_BOOT_ADD0 0x0000FFFFU
#define FLASH_OPTCR1_BOOT_ADD1 0xFFFF0000U
/******************************************************************************/
/* */
/* Flexible Memory Controller */
@ -6604,7 +6601,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
@ -6624,6 +6621,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
@ -7195,7 +7195,6 @@ typedef struct
#define SPDIFRX_DIR_THI 0x000013FFU /*!<Threshold LOW */
#define SPDIFRX_DIR_TLO 0x1FFF0000U /*!<Threshold HIGH */
/******************************************************************************/
/* */
/* SD host Interface */
@ -9535,6 +9534,7 @@ typedef struct
#define USB_OTG_PCGCCTL_GATECLK 0x00000002U /*!<Bit 0 */
#define USB_OTG_PCGCCTL_PHYSUSP 0x00000010U /*!<Bit 1 */
/******************************************************************************/
/* */
/* JPEG Encoder/Decoder */
@ -9793,28 +9793,28 @@ typedef struct
/******************************* GPIO Instances *******************************/
#define IS_GPIO_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == GPIOA) || \
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
#define IS_GPIO_AF_INSTANCE(__INSTANCE__) (((__INSTANCE__) == GPIOA) || \
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
/****************************** CEC Instances *********************************/
#define IS_CEC_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == CEC)
@ -9825,14 +9825,14 @@ typedef struct
/******************************** I2C Instances *******************************/
#define IS_I2C_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == I2C1) || \
((__INSTANCE__) == I2C2) || \
((__INSTANCE__) == I2C3) || \
((__INSTANCE__) == I2C4))
((__INSTANCE__) == I2C2) || \
((__INSTANCE__) == I2C3) || \
((__INSTANCE__) == I2C4))
/******************************** I2S Instances *******************************/
#define IS_I2S_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == SPI1) || \
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3))
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3))
/******************************* LPTIM Instances ********************************/
#define IS_LPTIM_INSTANCE(__INSTANCE__) ((__INSTANCE__) == LPTIM1)
@ -9846,6 +9846,7 @@ typedef struct
/****************************** MDIOS Instances ********************************/
#define IS_JPEG_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == JPEG)
/******************************* RNG Instances ********************************/
#define IS_RNG_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == RNG)
@ -9869,11 +9870,11 @@ typedef struct
/******************************** SPI Instances *******************************/
#define IS_SPI_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == SPI1) || \
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3) || \
((__INSTANCE__) == SPI4) || \
((__INSTANCE__) == SPI5) || \
((__INSTANCE__) == SPI6))
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3) || \
((__INSTANCE__) == SPI4) || \
((__INSTANCE__) == SPI5) || \
((__INSTANCE__) == SPI6))
/****************** TIM Instances : All supported instances *******************/
#define IS_TIM_INSTANCE(__INSTANCE__) (((__INSTANCE__) == TIM1) || \

View File

@ -2,8 +2,8 @@
******************************************************************************
* @file stm32f779xx.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:
@ -327,7 +327,6 @@ typedef struct
__IO uint32_t IER; /*!< CEC interrupt enable register, Address offset:0x14 */
}CEC_TypeDef;
/**
* @brief CRC calculation unit
*/
@ -454,7 +453,6 @@ typedef struct
__IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */
} DMA_TypeDef;
/**
* @brief DMA2D Controller
*/
@ -902,7 +900,6 @@ typedef struct
__IO uint32_t DIR; /*!< Debug Information register, Address offset: 0x18 */
} SPDIFRX_TypeDef;
/**
* @brief SD host Interface
*/
@ -1656,7 +1653,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)
@ -4218,7 +4215,6 @@ typedef struct
/******************** Bit definition for DMA2D_BGCLUT register **************/
/******************************************************************************/
/* */
/* External Interrupt/Event Controller */
@ -4545,6 +4541,7 @@ typedef struct
#define FLASH_OPTCR1_BOOT_ADD0 0x0000FFFFU
#define FLASH_OPTCR1_BOOT_ADD1 0xFFFF0000U
/******************************************************************************/
/* */
/* Flexible Memory Controller */
@ -6691,7 +6688,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
@ -6711,6 +6708,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
@ -7282,7 +7282,6 @@ typedef struct
#define SPDIFRX_DIR_THI 0x000013FFU /*!<Threshold LOW */
#define SPDIFRX_DIR_TLO 0x1FFF0000U /*!<Threshold HIGH */
/******************************************************************************/
/* */
/* SD host Interface */
@ -9622,6 +9621,7 @@ typedef struct
#define USB_OTG_PCGCCTL_GATECLK 0x00000002U /*!<Bit 0 */
#define USB_OTG_PCGCCTL_PHYSUSP 0x00000010U /*!<Bit 1 */
/******************************************************************************/
/* */
/* JPEG Encoder/Decoder */
@ -11069,28 +11069,28 @@ typedef struct
/******************************* GPIO Instances *******************************/
#define IS_GPIO_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == GPIOA) || \
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
#define IS_GPIO_AF_INSTANCE(__INSTANCE__) (((__INSTANCE__) == GPIOA) || \
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
((__INSTANCE__) == GPIOB) || \
((__INSTANCE__) == GPIOC) || \
((__INSTANCE__) == GPIOD) || \
((__INSTANCE__) == GPIOE) || \
((__INSTANCE__) == GPIOF) || \
((__INSTANCE__) == GPIOG) || \
((__INSTANCE__) == GPIOH) || \
((__INSTANCE__) == GPIOI) || \
((__INSTANCE__) == GPIOJ) || \
((__INSTANCE__) == GPIOK))
/****************************** CEC Instances *********************************/
#define IS_CEC_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == CEC)
@ -11101,14 +11101,14 @@ typedef struct
/******************************** I2C Instances *******************************/
#define IS_I2C_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == I2C1) || \
((__INSTANCE__) == I2C2) || \
((__INSTANCE__) == I2C3) || \
((__INSTANCE__) == I2C4))
((__INSTANCE__) == I2C2) || \
((__INSTANCE__) == I2C3) || \
((__INSTANCE__) == I2C4))
/******************************** I2S Instances *******************************/
#define IS_I2S_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == SPI1) || \
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3))
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3))
/******************************* LPTIM Instances ********************************/
#define IS_LPTIM_INSTANCE(__INSTANCE__) ((__INSTANCE__) == LPTIM1)
@ -11122,6 +11122,7 @@ typedef struct
/****************************** MDIOS Instances ********************************/
#define IS_JPEG_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == JPEG)
/******************************* RNG Instances ********************************/
#define IS_RNG_ALL_INSTANCE(__INSTANCE__) ((__INSTANCE__) == RNG)
@ -11145,11 +11146,11 @@ typedef struct
/******************************** SPI Instances *******************************/
#define IS_SPI_ALL_INSTANCE(__INSTANCE__) (((__INSTANCE__) == SPI1) || \
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3) || \
((__INSTANCE__) == SPI4) || \
((__INSTANCE__) == SPI5) || \
((__INSTANCE__) == SPI6))
((__INSTANCE__) == SPI2) || \
((__INSTANCE__) == SPI3) || \
((__INSTANCE__) == SPI4) || \
((__INSTANCE__) == SPI5) || \
((__INSTANCE__) == SPI6))
/****************** TIM Instances : All supported instances *******************/
#define IS_TIM_INSTANCE(__INSTANCE__) (((__INSTANCE__) == TIM1) || \

View File

@ -2,8 +2,8 @@
******************************************************************************
* @file stm32f7xx.h
* @author MCD Application Team
* @version V1.1.0
* @date 22-April-2016
* @version V1.1.2
* @date 23-September-2016
* @brief CMSIS STM32F7xx Device Peripheral Access Layer Header File.
*
* The file is the unique include file that the application programmer
@ -75,7 +75,8 @@
application
*/
#if !defined (STM32F756xx) && !defined (STM32F746xx) && !defined (STM32F745xx) && !defined (STM32F767xx) && \
!defined (STM32F769xx) && !defined (STM32F777xx) && !defined (STM32F779xx)
!defined (STM32F769xx) && !defined (STM32F777xx) && !defined (STM32F779xx) && !defined (STM32F722xx) && \
!defined (STM32F723xx) && !defined (STM32F732xx) && !defined (STM32F733xx)
/* #define STM32F756xx */ /*!< STM32F756VG, STM32F756ZG, STM32F756ZG, STM32F756IG, STM32F756BG,
STM32F756NG Devices */
/* #define STM32F746xx */ /*!< STM32F746VE, STM32F746VG, STM32F746ZE, STM32F746ZG, STM32F746IE, STM32F746IG,
@ -84,11 +85,16 @@
/* #define STM32F765xx */ /*!< STM32F765BI, STM32F765BG, STM32F765NI, STM32F765NG, STM32F765II, STM32F765IG,
STM32F765ZI, STM32F765ZG, STM32F765VI, STM32F765VG Devices */
/* #define STM32F767xx */ /*!< STM32F767BG, STM32F767BI, STM32F767IG, STM32F767II, STM32F767NG, STM32F767NI,
STM32F767VG, STM32F767VI, STM32F767ZG, STM32F767ZI, STM32F768AI Devices */
STM32F767VG, STM32F767VI, STM32F767ZG, STM32F767ZI Devices */
/* #define STM32F769xx */ /*!< STM32F769AG, STM32F769AI, STM32F769BG, STM32F769BI, STM32F769IG, STM32F769II,
STM32F769NG, STM32F769NI Devices */
/* #define STM32F777xx */ /*!< STM32F777VI, STM32F777ZI, STM32F777II, STM32F777BI, STM32F777NI, STM32F778AI Devices */
/* #define STM32F779xx */ /*!< STM32F779II, STM32F779BI, STM32F779NI, STM32F779AI Devices */
STM32F769NG, STM32F769NI, STM32F768AI Devices */
/* #define STM32F777xx */ /*!< STM32F777VI, STM32F777ZI, STM32F777II, STM32F777BI, STM32F777NI Devices */
/* #define STM32F779xx */ /*!< STM32F779II, STM32F779BI, STM32F779NI, STM32F779AI, STM32F778AI Devices */
/* #define STM32F722xx */ /*!< STM32F722IE, STM32F722ZE, STM32F722VE, STM32F722RE, STM32F722IC, STM32F722ZC,
STM32F722VC, STM32F722RC Devices */
/* #define STM32F723xx */ /*!< STM32F723IE, STM32F723ZE, STM32F723VE, STM32F723IC, STM32F723ZC, STM32F723VC Devices */
/* #define STM32F732xx */ /*!< STM32F732IE, STM32F732ZE, STM32F732VE, STM32F732RE Devices */
/* #define STM32F733xx */ /*!< STM32F733IE, STM32F733ZE, STM32F733VE Devices */
#endif
/* Tip: To avoid modifying this file each time you need to switch between these
@ -105,11 +111,11 @@
#endif /* USE_HAL_DRIVER */
/**
* @brief CMSIS Device version number V1.1.0
* @brief CMSIS Device version number V1.1.2
*/
#define __STM32F7_CMSIS_VERSION_MAIN (0x01) /*!< [31:24] main version */
#define __STM32F7_CMSIS_VERSION_SUB1 (0x01) /*!< [23:16] sub1 version */
#define __STM32F7_CMSIS_VERSION_SUB2 (0x00) /*!< [15:8] sub2 version */
#define __STM32F7_CMSIS_VERSION_SUB2 (0x02) /*!< [15:8] sub2 version */
#define __STM32F7_CMSIS_VERSION_RC (0x00) /*!< [7:0] release candidate */
#define __STM32F7_CMSIS_VERSION ((__STM32F7_CMSIS_VERSION_MAIN << 24)\
|(__STM32F7_CMSIS_VERSION_SUB1 << 16)\
@ -122,7 +128,15 @@
/** @addtogroup Device_Included
* @{
*/
#if defined(STM32F756xx)
#if defined(STM32F722xx)
#include "stm32f722xx.h"
#elif defined(STM32F723xx)
#include "stm32f723xx.h"
#elif defined(STM32F732xx)
#include "stm32f732xx.h"
#elif defined(STM32F733xx)
#include "stm32f733xx.h"
#elif defined(STM32F756xx)
#include "stm32f756xx.h"
#elif defined(STM32F746xx)
#include "stm32f746xx.h"

View File

@ -2,8 +2,8 @@
******************************************************************************
* @file system_stm32f7xx.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 System Source File for STM32F7xx devices.
******************************************************************************
* @attention

File diff suppressed because one or more lines are too long

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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 };
/*###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 { };

View File

@ -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 };

View File

@ -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 };

View File

@ -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 };
/*###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 { };

View File

@ -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 };

View File

@ -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 };

View File

@ -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 };
/*###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 { };

View File

@ -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 };

View File

@ -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 };

View File

@ -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 };
/*###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 { };

View File

@ -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 };

View File

@ -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 };

View File

@ -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 };
/*###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 { };

View File

@ -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 };

View File

@ -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 };

View File

@ -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 };
/*###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 { };

View File

@ -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 };

View File

@ -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 };

View File

@ -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 };
/*###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 { };

View File

@ -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 };

View File

@ -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 };

View File

@ -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 };
/*###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 { };

View File

@ -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 };

View File

@ -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 };

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

File diff suppressed because one or more lines are too long