Merge pull request #11198 from SteveCEvans/sce_rc2
[betaflight.git] / lib / main / STM32F4 / Drivers / STM32F4xx_HAL_Driver / Inc / stm32f4xx_hal_flash.h
blob38f2db87a1fa595827ce64a940d185fd6a84c77d
1 /**
2 ******************************************************************************
3 * @file stm32f4xx_hal_flash.h
4 * @author MCD Application Team
5 * @version V1.7.1
6 * @date 14-April-2017
7 * @brief Header file of FLASH HAL module.
8 ******************************************************************************
9 * @attention
11 * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
13 * Redistribution and use in source and binary forms, with or without modification,
14 * are permitted provided that the following conditions are met:
15 * 1. Redistributions of source code must retain the above copyright notice,
16 * this list of conditions and the following disclaimer.
17 * 2. Redistributions in binary form must reproduce the above copyright notice,
18 * this list of conditions and the following disclaimer in the documentation
19 * and/or other materials provided with the distribution.
20 * 3. Neither the name of STMicroelectronics nor the names of its contributors
21 * may be used to endorse or promote products derived from this software
22 * without specific prior written permission.
24 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
25 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
26 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
27 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
28 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
29 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
30 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
32 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
33 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
35 ******************************************************************************
36 */
38 /* Define to prevent recursive inclusion -------------------------------------*/
39 #ifndef __STM32F4xx_HAL_FLASH_H
40 #define __STM32F4xx_HAL_FLASH_H
42 #ifdef __cplusplus
43 extern "C" {
44 #endif
46 /* Includes ------------------------------------------------------------------*/
47 #include "stm32f4xx_hal_def.h"
49 /** @addtogroup STM32F4xx_HAL_Driver
50 * @{
53 /** @addtogroup FLASH
54 * @{
55 */
57 /* Exported types ------------------------------------------------------------*/
58 /** @defgroup FLASH_Exported_Types FLASH Exported Types
59 * @{
62 /**
63 * @brief FLASH Procedure structure definition
65 typedef enum
67 FLASH_PROC_NONE = 0U,
68 FLASH_PROC_SECTERASE,
69 FLASH_PROC_MASSERASE,
70 FLASH_PROC_PROGRAM
71 } FLASH_ProcedureTypeDef;
73 /**
74 * @brief FLASH handle Structure definition
76 typedef struct
78 __IO FLASH_ProcedureTypeDef ProcedureOnGoing; /*Internal variable to indicate which procedure is ongoing or not in IT context*/
80 __IO uint32_t NbSectorsToErase; /*Internal variable to save the remaining sectors to erase in IT context*/
82 __IO uint8_t VoltageForErase; /*Internal variable to provide voltage range selected by user in IT context*/
84 __IO uint32_t Sector; /*Internal variable to define the current sector which is erasing*/
86 __IO uint32_t Bank; /*Internal variable to save current bank selected during mass erase*/
88 __IO uint32_t Address; /*Internal variable to save address selected for program*/
90 HAL_LockTypeDef Lock; /* FLASH locking object */
92 __IO uint32_t ErrorCode; /* FLASH error code */
94 }FLASH_ProcessTypeDef;
96 /**
97 * @}
100 /* Exported constants --------------------------------------------------------*/
101 /** @defgroup FLASH_Exported_Constants FLASH Exported Constants
102 * @{
104 /** @defgroup FLASH_Error_Code FLASH Error Code
105 * @brief FLASH Error Code
106 * @{
108 #define HAL_FLASH_ERROR_NONE 0x00000000U /*!< No error */
109 #define HAL_FLASH_ERROR_RD 0x00000001U /*!< Read Protection error */
110 #define HAL_FLASH_ERROR_PGS 0x00000002U /*!< Programming Sequence error */
111 #define HAL_FLASH_ERROR_PGP 0x00000004U /*!< Programming Parallelism error */
112 #define HAL_FLASH_ERROR_PGA 0x00000008U /*!< Programming Alignment error */
113 #define HAL_FLASH_ERROR_WRP 0x00000010U /*!< Write protection error */
114 #define HAL_FLASH_ERROR_OPERATION 0x00000020U /*!< Operation Error */
116 * @}
119 /** @defgroup FLASH_Type_Program FLASH Type Program
120 * @{
122 #define FLASH_TYPEPROGRAM_BYTE 0x00000000U /*!< Program byte (8-bit) at a specified address */
123 #define FLASH_TYPEPROGRAM_HALFWORD 0x00000001U /*!< Program a half-word (16-bit) at a specified address */
124 #define FLASH_TYPEPROGRAM_WORD 0x00000002U /*!< Program a word (32-bit) at a specified address */
125 #define FLASH_TYPEPROGRAM_DOUBLEWORD 0x00000003U /*!< Program a double word (64-bit) at a specified address */
127 * @}
130 /** @defgroup FLASH_Flag_definition FLASH Flag definition
131 * @brief Flag definition
132 * @{
134 #define FLASH_FLAG_EOP FLASH_SR_EOP /*!< FLASH End of Operation flag */
135 #define FLASH_FLAG_OPERR FLASH_SR_SOP /*!< FLASH operation Error flag */
136 #define FLASH_FLAG_WRPERR FLASH_SR_WRPERR /*!< FLASH Write protected error flag */
137 #define FLASH_FLAG_PGAERR FLASH_SR_PGAERR /*!< FLASH Programming Alignment error flag */
138 #define FLASH_FLAG_PGPERR FLASH_SR_PGPERR /*!< FLASH Programming Parallelism error flag */
139 #define FLASH_FLAG_PGSERR FLASH_SR_PGSERR /*!< FLASH Programming Sequence error flag */
140 #if defined(FLASH_SR_RDERR)
141 #define FLASH_FLAG_RDERR FLASH_SR_RDERR /*!< Read Protection error flag (PCROP) */
142 #endif /* FLASH_SR_RDERR */
143 #define FLASH_FLAG_BSY FLASH_SR_BSY /*!< FLASH Busy flag */
145 * @}
148 /** @defgroup FLASH_Interrupt_definition FLASH Interrupt definition
149 * @brief FLASH Interrupt definition
150 * @{
152 #define FLASH_IT_EOP FLASH_CR_EOPIE /*!< End of FLASH Operation Interrupt source */
153 #define FLASH_IT_ERR 0x02000000U /*!< Error Interrupt source */
155 * @}
158 /** @defgroup FLASH_Program_Parallelism FLASH Program Parallelism
159 * @{
161 #define FLASH_PSIZE_BYTE 0x00000000U
162 #define FLASH_PSIZE_HALF_WORD 0x00000100U
163 #define FLASH_PSIZE_WORD 0x00000200U
164 #define FLASH_PSIZE_DOUBLE_WORD 0x00000300U
165 #define CR_PSIZE_MASK 0xFFFFFCFFU
167 * @}
170 /** @defgroup FLASH_Keys FLASH Keys
171 * @{
173 #define RDP_KEY ((uint16_t)0x00A5)
174 #define FLASH_KEY1 0x45670123U
175 #define FLASH_KEY2 0xCDEF89ABU
176 #define FLASH_OPT_KEY1 0x08192A3BU
177 #define FLASH_OPT_KEY2 0x4C5D6E7FU
179 * @}
183 * @}
186 /* Exported macro ------------------------------------------------------------*/
187 /** @defgroup FLASH_Exported_Macros FLASH Exported Macros
188 * @{
191 * @brief Set the FLASH Latency.
192 * @param __LATENCY__: FLASH Latency
193 * The value of this parameter depend on device used within the same series
194 * @retval none
196 #define __HAL_FLASH_SET_LATENCY(__LATENCY__) (*(__IO uint8_t *)ACR_BYTE0_ADDRESS = (uint8_t)(__LATENCY__))
199 * @brief Get the FLASH Latency.
200 * @retval FLASH Latency
201 * The value of this parameter depend on device used within the same series
203 #define __HAL_FLASH_GET_LATENCY() (READ_BIT((FLASH->ACR), FLASH_ACR_LATENCY))
206 * @brief Enable the FLASH prefetch buffer.
207 * @retval none
209 #define __HAL_FLASH_PREFETCH_BUFFER_ENABLE() (FLASH->ACR |= FLASH_ACR_PRFTEN)
212 * @brief Disable the FLASH prefetch buffer.
213 * @retval none
215 #define __HAL_FLASH_PREFETCH_BUFFER_DISABLE() (FLASH->ACR &= (~FLASH_ACR_PRFTEN))
218 * @brief Enable the FLASH instruction cache.
219 * @retval none
221 #define __HAL_FLASH_INSTRUCTION_CACHE_ENABLE() (FLASH->ACR |= FLASH_ACR_ICEN)
224 * @brief Disable the FLASH instruction cache.
225 * @retval none
227 #define __HAL_FLASH_INSTRUCTION_CACHE_DISABLE() (FLASH->ACR &= (~FLASH_ACR_ICEN))
230 * @brief Enable the FLASH data cache.
231 * @retval none
233 #define __HAL_FLASH_DATA_CACHE_ENABLE() (FLASH->ACR |= FLASH_ACR_DCEN)
236 * @brief Disable the FLASH data cache.
237 * @retval none
239 #define __HAL_FLASH_DATA_CACHE_DISABLE() (FLASH->ACR &= (~FLASH_ACR_DCEN))
242 * @brief Resets the FLASH instruction Cache.
243 * @note This function must be used only when the Instruction Cache is disabled.
244 * @retval None
246 #define __HAL_FLASH_INSTRUCTION_CACHE_RESET() do {FLASH->ACR |= FLASH_ACR_ICRST; \
247 FLASH->ACR &= ~FLASH_ACR_ICRST; \
248 }while(0U)
251 * @brief Resets the FLASH data Cache.
252 * @note This function must be used only when the data Cache is disabled.
253 * @retval None
255 #define __HAL_FLASH_DATA_CACHE_RESET() do {FLASH->ACR |= FLASH_ACR_DCRST; \
256 FLASH->ACR &= ~FLASH_ACR_DCRST; \
257 }while(0U)
259 * @brief Enable the specified FLASH interrupt.
260 * @param __INTERRUPT__ : FLASH interrupt
261 * This parameter can be any combination of the following values:
262 * @arg FLASH_IT_EOP: End of FLASH Operation Interrupt
263 * @arg FLASH_IT_ERR: Error Interrupt
264 * @retval none
266 #define __HAL_FLASH_ENABLE_IT(__INTERRUPT__) (FLASH->CR |= (__INTERRUPT__))
269 * @brief Disable the specified FLASH interrupt.
270 * @param __INTERRUPT__ : FLASH interrupt
271 * This parameter can be any combination of the following values:
272 * @arg FLASH_IT_EOP: End of FLASH Operation Interrupt
273 * @arg FLASH_IT_ERR: Error Interrupt
274 * @retval none
276 #define __HAL_FLASH_DISABLE_IT(__INTERRUPT__) (FLASH->CR &= ~(uint32_t)(__INTERRUPT__))
279 * @brief Get the specified FLASH flag status.
280 * @param __FLAG__: specifies the FLASH flags to check.
281 * This parameter can be any combination of the following values:
282 * @arg FLASH_FLAG_EOP : FLASH End of Operation flag
283 * @arg FLASH_FLAG_OPERR : FLASH operation Error flag
284 * @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag
285 * @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag
286 * @arg FLASH_FLAG_PGPERR: FLASH Programming Parallelism error flag
287 * @arg FLASH_FLAG_PGSERR: FLASH Programming Sequence error flag
288 * @arg FLASH_FLAG_RDERR : FLASH Read Protection error flag (PCROP) (*)
289 * @arg FLASH_FLAG_BSY : FLASH Busy flag
290 * (*) FLASH_FLAG_RDERR is not available for STM32F405xx/407xx/415xx/417xx devices
291 * @retval The new state of __FLAG__ (SET or RESET).
293 #define __HAL_FLASH_GET_FLAG(__FLAG__) ((FLASH->SR & (__FLAG__)))
296 * @brief Clear the specified FLASH flags.
297 * @param __FLAG__: specifies the FLASH flags to clear.
298 * This parameter can be any combination of the following values:
299 * @arg FLASH_FLAG_EOP : FLASH End of Operation flag
300 * @arg FLASH_FLAG_OPERR : FLASH operation Error flag
301 * @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag
302 * @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag
303 * @arg FLASH_FLAG_PGPERR: FLASH Programming Parallelism error flag
304 * @arg FLASH_FLAG_PGSERR: FLASH Programming Sequence error flag
305 * @arg FLASH_FLAG_RDERR : FLASH Read Protection error flag (PCROP) (*)
306 * (*) FLASH_FLAG_RDERR is not available for STM32F405xx/407xx/415xx/417xx devices
307 * @retval none
309 #define __HAL_FLASH_CLEAR_FLAG(__FLAG__) (FLASH->SR = (__FLAG__))
311 * @}
314 /* Include FLASH HAL Extension module */
315 #include "stm32f4xx_hal_flash_ex.h"
316 #include "stm32f4xx_hal_flash_ramfunc.h"
318 /* Exported functions --------------------------------------------------------*/
319 /** @addtogroup FLASH_Exported_Functions
320 * @{
322 /** @addtogroup FLASH_Exported_Functions_Group1
323 * @{
325 /* Program operation functions ***********************************************/
326 HAL_StatusTypeDef HAL_FLASH_Program(uint32_t TypeProgram, uint32_t Address, uint64_t Data);
327 HAL_StatusTypeDef HAL_FLASH_Program_IT(uint32_t TypeProgram, uint32_t Address, uint64_t Data);
328 /* FLASH IRQ handler method */
329 void HAL_FLASH_IRQHandler(void);
330 /* Callbacks in non blocking modes */
331 void HAL_FLASH_EndOfOperationCallback(uint32_t ReturnValue);
332 void HAL_FLASH_OperationErrorCallback(uint32_t ReturnValue);
334 * @}
337 /** @addtogroup FLASH_Exported_Functions_Group2
338 * @{
340 /* Peripheral Control functions **********************************************/
341 HAL_StatusTypeDef HAL_FLASH_Unlock(void);
342 HAL_StatusTypeDef HAL_FLASH_Lock(void);
343 HAL_StatusTypeDef HAL_FLASH_OB_Unlock(void);
344 HAL_StatusTypeDef HAL_FLASH_OB_Lock(void);
345 /* Option bytes control */
346 HAL_StatusTypeDef HAL_FLASH_OB_Launch(void);
348 * @}
351 /** @addtogroup FLASH_Exported_Functions_Group3
352 * @{
354 /* Peripheral State functions ************************************************/
355 uint32_t HAL_FLASH_GetError(void);
356 HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout);
358 * @}
362 * @}
364 /* Private types -------------------------------------------------------------*/
365 /* Private variables ---------------------------------------------------------*/
366 /** @defgroup FLASH_Private_Variables FLASH Private Variables
367 * @{
371 * @}
373 /* Private constants ---------------------------------------------------------*/
374 /** @defgroup FLASH_Private_Constants FLASH Private Constants
375 * @{
378 /**
379 * @brief ACR register byte 0 (Bits[7:0]) base address
381 #define ACR_BYTE0_ADDRESS 0x40023C00U
382 /**
383 * @brief OPTCR register byte 0 (Bits[7:0]) base address
385 #define OPTCR_BYTE0_ADDRESS 0x40023C14U
386 /**
387 * @brief OPTCR register byte 1 (Bits[15:8]) base address
389 #define OPTCR_BYTE1_ADDRESS 0x40023C15U
390 /**
391 * @brief OPTCR register byte 2 (Bits[23:16]) base address
393 #define OPTCR_BYTE2_ADDRESS 0x40023C16U
394 /**
395 * @brief OPTCR register byte 3 (Bits[31:24]) base address
397 #define OPTCR_BYTE3_ADDRESS 0x40023C17U
400 * @}
403 /* Private macros ------------------------------------------------------------*/
404 /** @defgroup FLASH_Private_Macros FLASH Private Macros
405 * @{
408 /** @defgroup FLASH_IS_FLASH_Definitions FLASH Private macros to check input parameters
409 * @{
411 #define IS_FLASH_TYPEPROGRAM(VALUE)(((VALUE) == FLASH_TYPEPROGRAM_BYTE) || \
412 ((VALUE) == FLASH_TYPEPROGRAM_HALFWORD) || \
413 ((VALUE) == FLASH_TYPEPROGRAM_WORD) || \
414 ((VALUE) == FLASH_TYPEPROGRAM_DOUBLEWORD))
416 * @}
420 * @}
423 /* Private functions ---------------------------------------------------------*/
424 /** @defgroup FLASH_Private_Functions FLASH Private Functions
425 * @{
429 * @}
433 * @}
437 * @}
440 #ifdef __cplusplus
442 #endif
444 #endif /* __STM32F4xx_HAL_FLASH_H */
446 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/