Merge pull request #10592 from iNavFlight/MrD_Update-parameter-description
[inav.git] / lib / main / AT32F43x / Drivers / AT32F43x_StdPeriph_Driver / inc / at32f435_437_flash.h
blob5f8650e30765ac62913dca748e47d48dab3453e3
1 /**
2 **************************************************************************
3 * @file at32f435_437_flash.h
4 * @version v2.1.0
5 * @date 2022-08-16
6 * @brief at32f435_437 flash header file
7 **************************************************************************
8 * Copyright notice & Disclaimer
10 * The software Board Support Package (BSP) that is made available to
11 * download from Artery official website is the copyrighted work of Artery.
12 * Artery authorizes customers to use, copy, and distribute the BSP
13 * software and its related documentation for the purpose of design and
14 * development in conjunction with Artery microcontrollers. Use of the
15 * software is governed by this copyright notice and the following disclaimer.
17 * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
18 * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
19 * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
20 * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
21 * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
22 * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
24 **************************************************************************
27 /* Define to prevent recursive inclusion -------------------------------------*/
28 #ifndef __AT32F435_437_FLASH_H
29 #define __AT32F435_437_FLASH_H
31 #ifdef __cplusplus
32 extern "C" {
33 #endif
36 /* Includes ------------------------------------------------------------------*/
37 #include "at32f435_437.h"
39 /** @addtogroup AT32F435_437_periph_driver
40 * @{
43 /** @addtogroup FLASH
44 * @{
47 /** @defgroup FLASH_exported_constants
48 * @{
51 /**
52 * @brief flash unlock keys
54 #define FLASH_UNLOCK_KEY1 ((uint32_t)0x45670123) /*!< flash operation unlock order key1 */
55 #define FLASH_UNLOCK_KEY2 ((uint32_t)0xCDEF89AB) /*!< flash operation unlock order key2 */
56 #define FAP_RELIEVE_KEY ((uint16_t)0x00A5) /*!< flash fap relieve key val */
57 #define SLIB_UNLOCK_KEY ((uint32_t)0xA35F6D24) /*!< flash slib operation unlock order key */
59 /**
60 * @brief flash bank address
62 #if defined (AT32F435CMU7) || defined (AT32F435CMT7) || defined (AT32F435RMT7) || \
63 defined (AT32F435VMT7) || defined (AT32F435ZMT7) || defined (AT32F437RMT7) || \
64 defined (AT32F437VMT7) || defined (AT32F437ZMT7)
65 #define FLASH_BANK1_START_ADDR ((uint32_t)0x08000000) /*!< flash start address of bank1 */
66 #define FLASH_BANK1_END_ADDR ((uint32_t)0x081FFFFF) /*!< flash end address of bank1 */
67 #define FLASH_BANK2_START_ADDR ((uint32_t)0x08200000) /*!< flash start address of bank2 */
68 #define FLASH_BANK2_END_ADDR ((uint32_t)0x083EFFFF) /*!< flash end address of bank2 */
69 #else
70 #define FLASH_BANK1_START_ADDR ((uint32_t)0x08000000) /*!< flash start address of bank1 */
71 #define FLASH_BANK1_END_ADDR ((uint32_t)0x0807FFFF) /*!< flash end address of bank1 */
72 #define FLASH_BANK2_START_ADDR ((uint32_t)0x08080000) /*!< flash start address of bank2 */
73 #define FLASH_BANK2_END_ADDR ((uint32_t)0x080FFFFF) /*!< flash end address of bank2 */
74 #endif
76 /**
77 * @brief flash flag
79 #define FLASH_OBF_FLAG FLASH_BANK1_OBF_FLAG /*!< flash operate busy flag */
80 #define FLASH_ODF_FLAG FLASH_BANK1_ODF_FLAG /*!< flash operate done flag */
81 #define FLASH_PRGMERR_FLAG FLASH_BANK1_PRGMERR_FLAG /*!< flash program error flag */
82 #define FLASH_EPPERR_FLAG FLASH_BANK1_EPPERR_FLAG /*!< flash erase/program protection error flag */
83 #define FLASH_BANK1_OBF_FLAG ((uint32_t)0x00000001) /*!< flash bank1 operate busy flag */
84 #define FLASH_BANK1_ODF_FLAG ((uint32_t)0x00000020) /*!< flash bank1 operate done flag */
85 #define FLASH_BANK1_PRGMERR_FLAG ((uint32_t)0x00000004) /*!< flash bank1 program error flag */
86 #define FLASH_BANK1_EPPERR_FLAG ((uint32_t)0x00000010) /*!< flash bank1 erase/program protection error flag */
87 #define FLASH_BANK2_OBF_FLAG ((uint32_t)0x10000001) /*!< flash bank2 operate busy flag */
88 #define FLASH_BANK2_ODF_FLAG ((uint32_t)0x10000020) /*!< flash bank2 operate done flag */
89 #define FLASH_BANK2_PRGMERR_FLAG ((uint32_t)0x10000004) /*!< flash bank2 program error flag */
90 #define FLASH_BANK2_EPPERR_FLAG ((uint32_t)0x10000010) /*!< flash bank2 erase/program protection error flag */
91 #define FLASH_USDERR_FLAG ((uint32_t)0x40000001) /*!< flash user system data error flag */
93 /**
94 * @brief flash interrupts
96 #define FLASH_ERR_INT FLASH_BANK1_ERR_INT /*!< flash error interrupt */
97 #define FLASH_ODF_INT FLASH_BANK1_ODF_INT /*!< flash operate done interrupt */
98 #define FLASH_BANK1_ERR_INT ((uint32_t)0x00000001) /*!< flash bank1 error interrupt */
99 #define FLASH_BANK1_ODF_INT ((uint32_t)0x00000002) /*!< flash bank1 operate done interrupt */
100 #define FLASH_BANK2_ERR_INT ((uint32_t)0x00000004) /*!< flash bank2 error interrupt */
101 #define FLASH_BANK2_ODF_INT ((uint32_t)0x00000008) /*!< flash bank2 operate done interrupt */
104 * @brief flash slib mask
106 #define FLASH_SLIB_START_SECTOR ((uint32_t)0x0000FFFF) /*!< flash slib start sector */
107 #define FLASH_SLIB_INST_START_SECTOR ((uint32_t)0x0000FFFF) /*!< flash slib i-bus area start sector */
108 #define FLASH_SLIB_END_SECTOR ((uint32_t)0xFFFF0000) /*!< flash slib end sector */
111 * @brief user system data wdt_ato
113 #define USD_WDT_ATO_DISABLE ((uint16_t)0x0001) /*!< wdt auto start disabled */
114 #define USD_WDT_ATO_ENABLE ((uint16_t)0x0000) /*!< wdt auto start enabled */
117 * @brief user system data depslp_rst
119 #define USD_DEPSLP_NO_RST ((uint16_t)0x0002) /*!< no reset generated when entering in deepsleep */
120 #define USD_DEPSLP_RST ((uint16_t)0x0000) /*!< reset generated when entering in deepsleep */
123 * @brief user system data stdby_rst
125 #define USD_STDBY_NO_RST ((uint16_t)0x0004) /*!< no reset generated when entering in standby */
126 #define USD_STDBY_RST ((uint16_t)0x0000) /*!< reset generated when entering in standby */
129 * @brief user system data btopt
131 #define FLASH_BOOT_FROM_BANK1 ((uint16_t)0x0008) /*!< boot from bank1 */
132 #define FLASH_BOOT_FROM_BANK2 ((uint16_t)0x0000) /*!< boot from bank 2 or bank 1,depending on the activation of the bank */
135 * @brief user system data wdt_depslp
137 #define USD_WDT_DEPSLP_CONTINUE ((uint16_t)0x0020) /*!< wdt continue count when entering in deepsleep */
138 #define USD_WDT_DEPSLP_STOP ((uint16_t)0x0000) /*!< wdt stop count when entering in deepsleep */
141 * @brief user system data wdt_stdby
143 #define USD_WDT_STDBY_CONTINUE ((uint16_t)0x0040) /*!< wdt continue count when entering in standby */
144 #define USD_WDT_STDBY_STOP ((uint16_t)0x0000) /*!< wdt stop count when entering in standby */
147 * @brief flash timeout definition
149 #define AT_ERASE_TIMEOUT ((uint32_t)0x80000000) /*!< internal flash erase operation timeout */
150 #define PROGRAMMING_TIMEOUT ((uint32_t)0x00100000) /*!< internal flash program operation timeout */
151 #define OPERATION_TIMEOUT ((uint32_t)0x10000000) /*!< flash common operation timeout */
154 * @brief set the flash clock divider definition
155 * @param div: the flash clock divider.
156 * this parameter can be one of the following values:
157 * - FLASH_CLOCK_DIV_2
158 * - FLASH_CLOCK_DIV_3
159 * - FLASH_CLOCK_DIV_4
161 #define flash_clock_divider_set(div) (FLASH->divr_bit.fdiv = div)
164 * @}
167 /** @defgroup FLASH_exported_types
168 * @{
172 * @brief flash usd eopb0 type
174 typedef enum
176 FLASH_EOPB0_SRAM_512K = 0x00, /*!< sram 512k, flash zw area 128k */
177 FLASH_EOPB0_SRAM_448K = 0x01, /*!< sram 448k, flash zw area 192k */
178 FLASH_EOPB0_SRAM_384K = 0x02, /*!< sram 384k, flash zw area 256k */
179 FLASH_EOPB0_SRAM_320K = 0x03, /*!< sram 320k, flash zw area 320k */
180 FLASH_EOPB0_SRAM_256K = 0x04, /*!< sram 256k, flash zw area 384k */
181 FLASH_EOPB0_SRAM_192K = 0x05, /*!< sram 192k, flash zw area 448k */
182 FLASH_EOPB0_SRAM_128K = 0x06 /*!< sram 128k, flash zw area 512k */
183 } flash_usd_eopb0_type;
186 * @brief flash clock divider type
188 typedef enum
190 FLASH_CLOCK_DIV_2 = 0x00, /*!< flash clock divide by 2 */
191 FLASH_CLOCK_DIV_3 = 0x01, /*!< flash clock divide by 3 */
192 FLASH_CLOCK_DIV_4 = 0x02 /*!< flash clock divide by 4 */
193 } flash_clock_divider_type;
196 * @brief flash status type
198 typedef enum
200 FLASH_OPERATE_BUSY = 0x00, /*!< flash status is operate busy */
201 FLASH_PROGRAM_ERROR = 0x01, /*!< flash status is program error */
202 FLASH_EPP_ERROR = 0x02, /*!< flash status is epp error */
203 FLASH_OPERATE_DONE = 0x03, /*!< flash status is operate done */
204 FLASH_OPERATE_TIMEOUT = 0x04 /*!< flash status is operate timeout */
205 } flash_status_type;
208 * @brief type define flash register all
210 typedef struct
213 * @brief flash psr register, offset:0x00
215 union
217 __IO uint32_t psr;
218 struct
220 __IO uint32_t reserved1 : 12;/* [11:0] */
221 __IO uint32_t nzw_bst : 1; /* [12] */
222 __IO uint32_t nzw_bst_sts : 1; /* [13] */
223 __IO uint32_t reserved2 : 18;/* [31:14] */
224 } psr_bit;
228 * @brief flash unlock register, offset:0x04
230 union
232 __IO uint32_t unlock;
233 struct
235 __IO uint32_t ukval : 32;/* [31:0] */
236 } unlock_bit;
240 * @brief flash usd unlock register, offset:0x08
242 union
244 __IO uint32_t usd_unlock;
245 struct
247 __IO uint32_t usd_ukval : 32;/* [31:0] */
248 } usd_unlock_bit;
252 * @brief flash sts register, offset:0x0C
254 union
256 __IO uint32_t sts;
257 struct
259 __IO uint32_t obf : 1; /* [0] */
260 __IO uint32_t reserved1 : 1; /* [1] */
261 __IO uint32_t prgmerr : 1; /* [2] */
262 __IO uint32_t reserved2 : 1; /* [3] */
263 __IO uint32_t epperr : 1; /* [4] */
264 __IO uint32_t odf : 1; /* [5] */
265 __IO uint32_t reserved3 : 26;/* [31:6] */
266 } sts_bit;
270 * @brief flash ctrl register, offset:0x10
272 union
274 __IO uint32_t ctrl;
275 struct
277 __IO uint32_t fprgm : 1; /* [0] */
278 __IO uint32_t secers : 1; /* [1] */
279 __IO uint32_t bankers : 1; /* [2] */
280 __IO uint32_t blkers : 1; /* [3] */
281 __IO uint32_t usdprgm : 1; /* [4] */
282 __IO uint32_t usders : 1; /* [5] */
283 __IO uint32_t erstr : 1; /* [6] */
284 __IO uint32_t oplk : 1; /* [7] */
285 __IO uint32_t reserved1 : 1; /* [8] */
286 __IO uint32_t usdulks : 1; /* [9] */
287 __IO uint32_t errie : 1; /* [10] */
288 __IO uint32_t reserved2 : 1; /* [11] */
289 __IO uint32_t odfie : 1; /* [12] */
290 __IO uint32_t reserved3 : 19;/* [31:13] */
291 } ctrl_bit;
295 * @brief flash addr register, offset:0x14
297 union
299 __IO uint32_t addr;
300 struct
302 __IO uint32_t fa : 32;/* [31:0] */
303 } addr_bit;
307 * @brief flash reserved1 register, offset:0x18
309 __IO uint32_t reserved1;
312 * @brief flash usd register, offset:0x1C
314 union
316 __IO uint32_t usd;
317 struct
319 __IO uint32_t usderr : 1; /* [0] */
320 __IO uint32_t fap : 1; /* [1] */
321 __IO uint32_t wdt_ato_en : 1; /* [2] */
322 __IO uint32_t depslp_rst : 1; /* [3] */
323 __IO uint32_t stdby_rst : 1; /* [4] */
324 __IO uint32_t btopt : 1; /* [5] */
325 __IO uint32_t reserved1 : 1; /* [6] */
326 __IO uint32_t wdt_depslp : 1; /* [7] */
327 __IO uint32_t wdt_stdby : 1; /* [8] */
328 __IO uint32_t reserved2 : 1; /* [9] */
329 __IO uint32_t user_d0 : 8; /* [17:10] */
330 __IO uint32_t user_d1 : 8; /* [25:18] */
331 __IO uint32_t reserved3 : 6; /* [31:26] */
332 } usd_bit;
336 * @brief flash epps0 register, offset:0x20
338 union
340 __IO uint32_t epps0;
341 struct
343 __IO uint32_t epps : 32;/* [31:0] */
344 } epps0_bit;
348 * @brief flash reserved2 register, offset:0x28~0x24
350 __IO uint32_t reserved2[2];
353 * @brief flash epps1 register, offset:0x2C
355 union
357 __IO uint32_t epps1;
358 struct
360 __IO uint32_t epps : 32;/* [31:0] */
361 } epps1_bit;
365 * @brief flash reserved3 register, offset:0x40~0x30
367 __IO uint32_t reserved3[5];
370 * @brief flash unlock2 register, offset:0x44
372 union
374 __IO uint32_t unlock2;
375 struct
377 __IO uint32_t ukval : 32;/* [31:0] */
378 } unlock2_bit;
382 * @brief flash reserved4 register, offset:0x48
384 __IO uint32_t reserved4;
387 * @brief flash sts2 register, offset:0x4C
389 union
391 __IO uint32_t sts2;
392 struct
394 __IO uint32_t obf : 1; /* [0] */
395 __IO uint32_t reserved1 : 1; /* [1] */
396 __IO uint32_t prgmerr : 1; /* [2] */
397 __IO uint32_t reserved2 : 1; /* [3] */
398 __IO uint32_t epperr : 1; /* [4] */
399 __IO uint32_t odf : 1; /* [5] */
400 __IO uint32_t reserved3 : 26;/* [31:6] */
401 } sts2_bit;
405 * @brief flash ctrl2 register, offset:0x50
407 union
409 __IO uint32_t ctrl2;
410 struct
412 __IO uint32_t fprgm : 1; /* [0] */
413 __IO uint32_t secers : 1; /* [1] */
414 __IO uint32_t bankers : 1; /* [2] */
415 __IO uint32_t blkers : 1; /* [3] */
416 __IO uint32_t reserved1 : 2; /* [5:4] */
417 __IO uint32_t erstr : 1; /* [6] */
418 __IO uint32_t oplk : 1; /* [7] */
419 __IO uint32_t reserved2 : 2; /* [9:8] */
420 __IO uint32_t errie : 1; /* [10] */
421 __IO uint32_t reserved3 : 1; /* [11] */
422 __IO uint32_t odfie : 1; /* [12] */
423 __IO uint32_t reserved4 : 19;/* [31:13] */
424 } ctrl2_bit;
428 * @brief flash addr2 register, offset:0x54
430 union
432 __IO uint32_t addr2;
433 struct
435 __IO uint32_t fa : 32;/* [31:0] */
436 } addr2_bit;
440 * @brief flash contr register, offset:0x58
442 union
444 __IO uint32_t contr;
445 struct
447 __IO uint32_t reserved1 : 31;/* [30:0] */
448 __IO uint32_t fcontr_en : 1; /* [31] */
449 } contr_bit;
453 * @brief flash reserved5 register, offset:0x5C
455 __IO uint32_t reserved5;
458 * @brief flash divr register, offset:0x60
460 union
462 __IO uint32_t divr;
463 struct
465 __IO uint32_t fdiv : 2; /* [1:0] */
466 __IO uint32_t reserved1 : 2; /* [3:2] */
467 __IO uint32_t fdiv_sts : 2; /* [5:4] */
468 __IO uint32_t reserved2 : 26;/* [31:6] */
469 } divr_bit;
473 * @brief flash reserved6 register, offset:0xC4~0x64
475 __IO uint32_t reserved6[25];
478 * @brief flash slib_sts2 register, offset:0xC8
480 union
482 __IO uint32_t slib_sts2;
483 struct
485 __IO uint32_t slib_inst_ss : 16;/* [15:0] */
486 __IO uint32_t reserved1 : 16;/* [31:16] */
487 } slib_sts2_bit;
491 * @brief flash slib_sts0 register, offset:0xCC
493 union
495 __IO uint32_t slib_sts0;
496 struct
498 __IO uint32_t reserved1 : 3; /* [2:0] */
499 __IO uint32_t slib_enf : 1; /* [3] */
500 __IO uint32_t reserved2 : 28;/* [31:4] */
501 } slib_sts0_bit;
505 * @brief flash slib_sts1 register, offset:0xD0
507 union
509 __IO uint32_t slib_sts1;
510 struct
512 __IO uint32_t slib_ss : 16;/* [15:0] */
513 __IO uint32_t slib_es : 16;/* [31:16] */
514 } slib_sts1_bit;
518 * @brief flash slib_pwd_clr register, offset:0xD4
520 union
522 __IO uint32_t slib_pwd_clr;
523 struct
525 __IO uint32_t slib_pclr_val : 32;/* [31:0] */
526 } slib_pwd_clr_bit;
530 * @brief flash slib_misc_sts register, offset:0xD8
532 union
534 __IO uint32_t slib_misc_sts;
535 struct
537 __IO uint32_t slib_pwd_err : 1; /* [0] */
538 __IO uint32_t slib_pwd_ok : 1; /* [1] */
539 __IO uint32_t slib_ulkf : 1; /* [2] */
540 __IO uint32_t reserved1 : 13;/* [15:3] */
541 __IO uint32_t slib_rcnt : 9; /* [24:16] */
542 __IO uint32_t reserved2 : 7; /* [31:25] */
543 } slib_misc_sts_bit;
547 * @brief flash slib_set_pwd register, offset:0xDC
549 union
551 __IO uint32_t slib_set_pwd;
552 struct
554 __IO uint32_t slib_pset_val : 32;/* [31:0] */
555 } slib_set_pwd_bit;
559 * @brief flash slib_set_range0 register, offset:0xE0
561 union
563 __IO uint32_t slib_set_range0;
564 struct
566 __IO uint32_t slib_ss_set : 16;/* [15:0] */
567 __IO uint32_t slib_es_set : 16;/* [31:16] */
568 } slib_set_range0_bit;
572 * @brief flash slib_set_range1 register, offset:0xE4
574 union
576 __IO uint32_t slib_set_range1;
577 struct
579 __IO uint32_t slib_iss_set : 16;/* [15:0] */
580 __IO uint32_t reserved1 : 15;/* [30:16] */
581 __IO uint32_t set_slib_strt : 1; /* [31] */
582 } slib_set_range1_bit;
586 * @brief flash reserved7 register, offset:0xEC~0xE8
588 __IO uint32_t reserved7[2];
591 * @brief flash slib_unlock register, offset:0xF0
593 union
595 __IO uint32_t slib_unlock;
596 struct
598 __IO uint32_t slib_ukval : 32;/* [31:0] */
599 } slib_unlock_bit;
603 * @brief flash crc_ctrl register, offset:0xF4
605 union
607 __IO uint32_t crc_ctrl;
608 struct
610 __IO uint32_t crc_ss : 12;/* [11:0] */
611 __IO uint32_t crc_sn : 12;/* [23:12] */
612 __IO uint32_t reserved1 : 7; /* [30:24] */
613 __IO uint32_t crc_strt : 1; /* [31] */
614 } crc_ctrl_bit;
618 * @brief flash crc_chkr register, offset:0xF8
620 union
622 __IO uint32_t crc_chkr;
623 struct
625 __IO uint32_t crc_chkr : 32;/* [31:0] */
626 } crc_chkr_bit;
629 } flash_type;
632 * @brief user system data
634 typedef struct
636 __IO uint16_t fap;
637 __IO uint16_t ssb;
638 __IO uint16_t data0;
639 __IO uint16_t data1;
640 __IO uint16_t epp0;
641 __IO uint16_t epp1;
642 __IO uint16_t epp2;
643 __IO uint16_t epp3;
644 __IO uint16_t eopb0;
645 __IO uint16_t reserved1;
646 __IO uint16_t epp4;
647 __IO uint16_t epp5;
648 __IO uint16_t epp6;
649 __IO uint16_t epp7;
650 __IO uint16_t reserved2[12];
651 __IO uint16_t qspikey[8];
652 } usd_type;
655 * @}
658 #define FLASH ((flash_type *) FLASH_REG_BASE)
659 #define USD ((usd_type *) USD_BASE)
661 /** @defgroup FLASH_exported_functions
662 * @{
665 flag_status flash_flag_get(uint32_t flash_flag);
666 void flash_flag_clear(uint32_t flash_flag);
667 flash_status_type flash_operation_status_get(void);
668 flash_status_type flash_bank1_operation_status_get(void);
669 flash_status_type flash_bank2_operation_status_get(void);
670 flash_status_type flash_operation_wait_for(uint32_t time_out);
671 flash_status_type flash_bank1_operation_wait_for(uint32_t time_out);
672 flash_status_type flash_bank2_operation_wait_for(uint32_t time_out);
673 void flash_unlock(void);
674 void flash_bank1_unlock(void);
675 void flash_bank2_unlock(void);
676 void flash_lock(void);
677 void flash_bank1_lock(void);
678 void flash_bank2_lock(void);
679 flash_status_type flash_sector_erase(uint32_t sector_address);
680 flash_status_type flash_block_erase(uint32_t block_address);
681 flash_status_type flash_internal_all_erase(void);
682 flash_status_type flash_bank1_erase(void);
683 flash_status_type flash_bank2_erase(void);
684 flash_status_type flash_user_system_data_erase(void);
685 flash_status_type flash_eopb0_config(flash_usd_eopb0_type data);
686 flash_status_type flash_word_program(uint32_t address, uint32_t data);
687 flash_status_type flash_halfword_program(uint32_t address, uint16_t data);
688 flash_status_type flash_byte_program(uint32_t address, uint8_t data);
689 flash_status_type flash_user_system_data_program(uint32_t address, uint8_t data);
690 flash_status_type flash_epp_set(uint32_t *sector_bits);
691 void flash_epp_status_get(uint32_t *sector_bits);
692 flash_status_type flash_fap_enable(confirm_state new_state);
693 flag_status flash_fap_status_get(void);
694 flash_status_type flash_ssb_set(uint8_t usd_ssb);
695 uint8_t flash_ssb_status_get(void);
696 void flash_interrupt_enable(uint32_t flash_int, confirm_state new_state);
697 flash_status_type flash_slib_enable(uint32_t pwd, uint16_t start_sector, uint16_t inst_start_sector, uint16_t end_sector);
698 error_status flash_slib_disable(uint32_t pwd);
699 uint32_t flash_slib_remaining_count_get(void);
700 flag_status flash_slib_state_get(void);
701 uint16_t flash_slib_start_sector_get(void);
702 uint16_t flash_slib_inststart_sector_get(void);
703 uint16_t flash_slib_end_sector_get(void);
704 uint32_t flash_crc_calibrate(uint32_t start_sector, uint32_t sector_cnt);
705 void flash_nzw_boost_enable(confirm_state new_state);
706 void flash_continue_read_enable(confirm_state new_state);
709 * @}
713 * @}
717 * @}
720 #ifdef __cplusplus
722 #endif
724 #endif